1
0
mirror of https://github.com/DCC-EX/CommandStation-EX.git synced 2024-11-22 23:56:13 +01:00

Nano every2 (#129)

* Start adding back unowifi stuffz

* Uno Wifi compiling

* Fixes for compile arduino unowifi r2

* FlasString and Timers for Uno Wifi

ALL these changes should be portable back to master

* Remove extra timer that was already added

* Changed to EveryTimerB

* Add everytimerb.h

* Cleanup

* Linear address <a> cmd

* Allow lower case keywords

* Add the F define to be on safe side if it is not present in the library core code

* Clean simple Timer interface

Removes overkill files, puts all timer in a single small file. (DCCTimer)

* Timer port

* Timer working

And slow wave command removed

* Correcting non-portables merged from master

* Wave-state machine ( part 11)

* Microtuning waveform

Significant reduction in code paths and call overheads

* Current check cleanup

* Fix no-loco id

Has to handle -1 correctly

* fix wrong format letter

* redo flow through wifisetup again

* version++

* bugfixes wifi setup

* Retry harder for AP mode

* Remove unued if

* DIO2 replacement

Currently for writing signal pins during waveform.

* Drop analogReadFast (see DCCTimer)

AnalogRead speed set in DCCTimer for ease of porting.
Code tidy and diagnostics in MotorDriver

* UNTESTED fast power,brake,fault pins

* Distunguish between in/out of FASTPIN

* minor performance tweaks

* Config comments and example use

* Config/example loading

* IP/PORT on LCD

* Ethernet simulated mac

Plus fixed listening port

* Github SHA

* Committing a SHA

* Fix for nano compile

* Comments and a reliability fix.

* UnoRev2 protection

* PWM pin implementation

* fix wifi setup issue

* Reinstate IP_PORT

* Wifi channel and code cleaninga

* Reduce duplicated F() macros

Compiler isn't as clever as one might expect

* Committing a SHA

* Update config.example.h

Add comment to wifi channel section

* Committing a SHA

* Handle shields with common fault pins (Pololu)

* Committing a SHA

* remove warning

* Committing a SHA

* only do the sha generation on master

* yaml syntax

* Fast SSD1306 OLED driver

Incorporate code from SSD1306Ascii library to speed up OLED screen updates, reduce memory requirements and eliminate some library dependences.

* Fix auto-configure from cold boot.

Add call to Wire.begin().

* Update comment for OLED_DRIVER define.

* Update MotorDrivers.h

Add a motor board definition for using the IBT_2 board for a high current to the main track and keep the Arduino Motor Shield for operating the programming track.

* Committing a SHA

* Fix missing F  in motor drivers

* JOIN relay pin

* Swap Join Relay high/low

* Hide WIFI_CONNECT_TIMEOUT

This is not what the config suggests it is...  The timeout is in the ES and defaults to 15 seconds. Abandoning it early leads to confused setup.

* Enhance OLED/LCD speed

Write one character or position command per loop entry so as not to hold up the loop.  Add support for SH1106 OLED as 132x64 size option.

* Enhance OLED/LCD speed

* Delete comment about OLED on UNO.

* Trim unwanted code

* Handle display types correctly

* Update comments

* Speed up OLED writes

Add new flushDisplay() to end any in-progress I2C transaction.  Previously, an redundant command was sent that ended the in-progress transaction but also sent another complete, but unnecessary, transaction.

* Comments and copyright update

* Reduce RAM and flash requirement a few more bytes.

* Move statics into LCDDisplay class, and reduce RAM.

Some state variables were static in LCDDisplay.write().  Moved to class members.  Also, types of data items like row, column & character position changed to int8_t to save a few bytes of RAM.

* Type lcdCols and lcdRows to unsigned.

Since lcdCols is normally 128, it needs to be uint8_t, not int8_t.

* remove timeout from user config

* faultpin is common only if it exists ; make code prettier

* Rationalisation of SSD1306 driver

Merge SSD1306AsciiWire.cpp into SSD1306Ascii.cpp and rename SSD1306AsciiWire.h as SSD1306Ascii.h.
Merge allFonts.h into System5x7.h and rename as SSD1306font.h.
Move all SSD1306 files into root folder to facilitate compilation in Arduino IDE.

* Fix some font attributes as const.

* Remove unused initialisation sequences for tiny oled screens

* Add m_ to variables

* Bump up I2C speed

Speed was 100kHz (default).  Max for OLEDis 400kHz.

* Revert "Bump up I2C speed"

This reverts commit 1c1168f433.

* Bump up I2C speed

Speed was 100kHz (default). Max for OLEDis 400kHz.

* Drop duplicate DIAG

* ignore mySetup.h files

* Restore uno to default_envs

Restore uno (previously commented out) to default_envs.

* Update objdump.bat

Allows other editors as Notepad is very slow on large files

* Prog Track overload during cv read

* Faster LCD Driver

Extract LCD driver from library;
Trim unused functionality;
Reduce I2C communications to minimum;
Speed up I2C clock to 400kHz.

* Update config.example.h

Add IBT_2_WITH_ARDUINO to example config

* Update config.example.h

* Screen enhancements (#126)

* Add I2CManager to coordinate I2C shared parameters.

* Add use of I2CManager, and experimental scrolling strategies.

New scrolling capability by defining SCROLLMODE in Config.h to 0 (original), 1 (by page) or 2 (by line).  If not defined, defaults to 0.

* Scrolling updates

New scrolling capability by defining SCROLLMODE in Config.h to 0 (original), 1 (by page) or 2 (by line). If not defined, defaults to 0.
Reformat.

* Add I2CManager calls. Remove unnecessary delays.

* Add I2CManager calls, remove unnecessary I2C delays.

* SSD1306: Move methods from .h to .cpp and reformat.

* Fix compiler warning in LiquidCrystal_I2C

* Allow forcing of I2C clock speed.

New method forceClock allows the I2C speed to be overridden.  For example, if the I2C bus is long then the speed can be forced lower.  It can also be forced higher to gain performance if devices are capable.

* Make Config.h conditionally included.

Allow for non-existence of Config.h.

* Correct scrolling and allow longer messages

Correct the handling of scrolling in scrollmode 1 to avoid a blank page being displayed.  Also, allow MAX_MSG_SIZE to be optionally configured to override maximum message length on screens.

* compiler warning on uno

Co-authored-by: dexslab <dex35803@gmail.com>
Co-authored-by: Asbelos <asbelos@btinternet.com>
Co-authored-by: Harald Barth <haba@kth.se>
Co-authored-by: Neil McKechnie <neilmck999@gmail.com>
Co-authored-by: Neil McKechnie <75813993+Neil-McK@users.noreply.github.com>
This commit is contained in:
Fred 2021-03-07 15:58:35 -05:00 committed by GitHub
parent 781d0325af
commit 4861e592c7
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
56 changed files with 2324 additions and 1560 deletions

4
.gitignore vendored
View File

@ -6,4 +6,6 @@ Release/*
.gcc-flags.json .gcc-flags.json
.pio/ .pio/
.vscode/ .vscode/
config.h config.h
.vscode/extensions.json
mySetup.h

View File

@ -1,194 +0,0 @@
#ifndef ATMEGA2560Timer_h
#define ATMEGA2560Timer_h
#include "../VirtualTimer.h"
#include <Arduino.h>
class Timer : public VirtualTimer {
private:
int pwmPeriod;
unsigned long timer_resolution;
unsigned char clockSelectBits;
int timer_num;
unsigned long lastMicroseconds;
public:
void (*isrCallback)();
Timer(int timer_num) {
switch (timer_num)
{
case 1:
case 3:
case 4:
case 5:
timer_resolution = 65536;
break;
}
this->timer_num = timer_num;
lastMicroseconds = 0;
}
void initialize() {
switch (timer_num)
{
case 1:
TCCR1B = _BV(WGM13) | _BV(WGM12);
TCCR1A = _BV(WGM11);
break;
case 3:
TCCR3B = _BV(WGM33) | _BV(WGM32);
TCCR3A = _BV(WGM31);
break;
case 4:
TCCR4B = _BV(WGM43) | _BV(WGM42);
TCCR4A = _BV(WGM41);
break;
case 5:
TCCR5B = _BV(WGM53) | _BV(WGM52);
TCCR5A = _BV(WGM51);
break;
}
}
void setPeriod(unsigned long microseconds) {
if(microseconds == lastMicroseconds)
return;
lastMicroseconds = microseconds;
const unsigned long cycles = (F_CPU / 1000000) * microseconds;
if (cycles < timer_resolution) {
clockSelectBits = 1 << 0;
pwmPeriod = cycles;
} else
if (cycles < timer_resolution * 8) {
clockSelectBits = 1 << 1;
pwmPeriod = cycles / 8;
} else
if (cycles < timer_resolution * 64) {
clockSelectBits = (1 << 0) | (1 << 1);
pwmPeriod = cycles / 64;
} else
if (cycles < timer_resolution * 256) {
clockSelectBits = 1 << 2;
pwmPeriod = cycles / 256;
} else
if (cycles < timer_resolution * 1024) {
clockSelectBits = (1 << 2) | (1 << 0);
pwmPeriod = cycles / 1024;
} else {
clockSelectBits = (1 << 2) | (1 << 0);
pwmPeriod = timer_resolution - 1;
}
switch (timer_num)
{
case 1:
ICR1 = pwmPeriod;
TCCR1B = _BV(WGM13) | _BV(WGM12) | clockSelectBits;
break;
case 3:
ICR3 = pwmPeriod;
TCCR3B = _BV(WGM33) | _BV(WGM32) | clockSelectBits;
break;
case 4:
ICR4 = pwmPeriod;
TCCR4B = _BV(WGM43) | _BV(WGM42) | clockSelectBits;
break;
case 5:
ICR5 = pwmPeriod;
TCCR5B = _BV(WGM53) | _BV(WGM52) | clockSelectBits;
break;
}
}
void start() {
switch (timer_num)
{
case 1:
TCCR1B = 0;
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
TCCR1B = _BV(WGM13) | _BV(WGM12) | clockSelectBits;
break;
case 3:
TCCR3B = 0;
TCNT3 = 0; // TODO: does this cause an undesired interrupt?
TCCR3B = _BV(WGM33) | _BV(WGM32) | clockSelectBits;
break;
case 4:
TCCR4B = 0;
TCNT4 = 0; // TODO: does this cause an undesired interrupt?
TCCR4B = _BV(WGM43) | _BV(WGM42) | clockSelectBits;
break;
case 5:
TCCR5B = 0;
TCNT5 = 0; // TODO: does this cause an undesired interrupt?
TCCR5B = _BV(WGM53) | _BV(WGM52) | clockSelectBits;
break;
}
}
void stop() {
switch (timer_num)
{
case 1:
TCCR1B = _BV(WGM13) | _BV(WGM12);
break;
case 3:
TCCR3B = _BV(WGM33) | _BV(WGM32);
break;
case 4:
TCCR4B = _BV(WGM43) | _BV(WGM42);
break;
case 5:
TCCR5B = _BV(WGM53) | _BV(WGM52);
break;
}
}
void attachInterrupt(void (*isr)()) {
isrCallback = isr;
switch (timer_num)
{
case 1:
TIMSK1 = _BV(TOIE1);
break;
case 3:
TIMSK3 = _BV(TOIE3);
break;
case 4:
TIMSK4 = _BV(TOIE4);
break;
case 5:
TIMSK5 = _BV(TOIE5);
break;
}
}
void detachInterrupt() {
switch (timer_num)
{
case 1:
TIMSK1 = 0;
break;
case 3:
TIMSK3 = 0;
break;
case 4:
TIMSK4 = 0;
break;
case 5:
TIMSK5 = 0;
break;
}
}
};
extern Timer TimerA;
extern Timer TimerB;
extern Timer TimerC;
extern Timer TimerD;
#endif

View File

@ -1,208 +0,0 @@
#ifndef ATMEGA328Timer_h
#define ATMEGA328Timer_h
#include "../VirtualTimer.h"
#include <Arduino.h>
class Timer : public VirtualTimer {
private:
int pwmPeriod;
unsigned long timer_resolution;
unsigned char clockSelectBits;
int timer_num;
unsigned long lastMicroseconds;
public:
void (*isrCallback)();
Timer(int timer_num) {
switch (timer_num)
{
//case 0:
case 2:
timer_resolution = 256;
break;
case 1:
timer_resolution = 65536;
break;
}
this->timer_num = timer_num;
lastMicroseconds = 0;
}
void initialize() {
switch (timer_num)
{
// case 0:
// TCCR0B = _BV(WGM02);
// TCCR0A = _BV(WGM00) | _BV(WGM01);
// break;
case 1:
TCCR1B = _BV(WGM13) | _BV(WGM12);
TCCR1A = _BV(WGM11);
break;
case 2:
TCCR2B = _BV(WGM22);
TCCR2A = _BV(WGM20) | _BV(WGM21);
break;
}
}
void setPeriod(unsigned long microseconds) {
if(microseconds == lastMicroseconds)
return;
lastMicroseconds = microseconds;
const unsigned long cycles = (F_CPU / 1000000) * microseconds;
switch(timer_num) {
case 2:
if (cycles < timer_resolution) {
clockSelectBits = 1 << 0;
pwmPeriod = cycles;
} else
if (cycles < timer_resolution * 8) {
clockSelectBits = 1 << 1;
pwmPeriod = cycles / 8;
} else
if (cycles < timer_resolution * 32) {
clockSelectBits = 1 << 0 | 1 << 1;
pwmPeriod = cycles / 32;
} else
if (cycles < timer_resolution * 64) {
clockSelectBits = 1 << 2;
pwmPeriod = cycles / 64;
} else
if (cycles < timer_resolution * 128) {
clockSelectBits = 1 << 2 | 1 << 0;
pwmPeriod = cycles / 128;
} else
if (cycles < timer_resolution * 256) {
clockSelectBits = 1 << 2 | 1 << 1;
pwmPeriod = cycles / 256;
} else
if (cycles < timer_resolution * 1024) {
clockSelectBits = 1 << 2 | 1 << 1 | 1 << 0;
pwmPeriod = cycles / 1024;
} else {
clockSelectBits = 1 << 2 | 1 << 1 | 1 << 0;
pwmPeriod = timer_resolution - 1;
}
break;
//case 0:
case 1:
if (cycles < timer_resolution) {
clockSelectBits = 1 << 0;
pwmPeriod = cycles;
} else
if (cycles < timer_resolution * 8) {
clockSelectBits = 1 << 1;
pwmPeriod = cycles / 8;
} else
if (cycles < timer_resolution * 64) {
clockSelectBits = (1 << 0) | (1 << 1);
pwmPeriod = cycles / 64;
} else
if (cycles < timer_resolution * 256) {
clockSelectBits = 1 << 2;
pwmPeriod = cycles / 256;
} else
if (cycles < timer_resolution * 1024) {
clockSelectBits = (1 << 2) | (1 << 0);
pwmPeriod = cycles / 1024;
} else {
clockSelectBits = (1 << 2) | (1 << 0);
pwmPeriod = timer_resolution - 1;
}
break;
}
switch (timer_num)
{
// case 0:
// OCR0A = pwmPeriod;
// TCCR0B = _BV(WGM02) | clockSelectBits;
// break;
case 1:
ICR1 = pwmPeriod;
TCCR1B = _BV(WGM13) | _BV(WGM12) | clockSelectBits;
break;
case 2:
OCR2A = pwmPeriod;
TCCR2B = _BV(WGM22) | clockSelectBits;
break;
}
}
void start() {
switch (timer_num)
{
// case 0:
// TCCR0B = 0;
// TCNT0 = 0; // TODO: does this cause an undesired interrupt?
// TCCR0B = _BV(WGM02) | clockSelectBits;
// break;
case 1:
TCCR1B = 0;
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
TCCR1B = _BV(WGM13) | _BV(WGM12) | clockSelectBits;
break;
case 2:
TCCR2B = 0;
TCNT2 = 0; // TODO: does this cause an undesired interrupt?
TCCR2B = _BV(WGM22) | clockSelectBits;
break;
}
}
void stop() {
switch (timer_num)
{
// case 0:
// TCCR0B = _BV(WGM02);
// break;
case 1:
TCCR1B = _BV(WGM13) | _BV(WGM12);
break;
case 2:
TCCR2B = _BV(WGM22);
break;
}
}
void attachInterrupt(void (*isr)()) {
isrCallback = isr;
switch (timer_num)
{
// case 0:
// TIMSK0 = _BV(TOIE0);
// break;
case 1:
TIMSK1 = _BV(TOIE1);
break;
case 2:
TIMSK2 = _BV(TOIE2);
break;
}
}
void detachInterrupt() {
switch (timer_num)
{
// case 0:
// TIMSK0 = 0;
// break;
case 1:
TIMSK1 = 0;
break;
case 2:
TIMSK2 = 0;
break;
}
}
};
extern Timer TimerA;
extern Timer TimerB;
#endif

View File

@ -1,37 +0,0 @@
/*
* AnalogReadFast.h
*
* Copyright (C) 2016 Albert van Dalen http://www.avdweb.nl
*
* This file is part of CommandStation.
*
* CommandStation 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.
*
* CommandStation 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 COMMANDSTATION_DCC_ANALOGREADFAST_H_
#define COMMANDSTATION_DCC_ANALOGREADFAST_H_
#include <Arduino.h>
int inline analogReadFast(uint8_t ADCpin);
int inline analogReadFast(uint8_t ADCpin)
{ byte ADCSRAoriginal = ADCSRA;
ADCSRA = (ADCSRA & B11111000) | 4;
int adc = analogRead(ADCpin);
ADCSRA = ADCSRAoriginal;
return adc;
}
#endif // COMMANDSTATION_DCC_ANALOGREADFAST_H_

View File

@ -1,18 +0,0 @@
// This file is copied from https://github.com/davidcutting42/ArduinoTimers
// All Credit and copyright David Cutting
// The files included below come from the same source.
// This library had been included with the DCC code to avoid issues with
// library management for inexperienced users. "It just works (TM)"
#ifndef ArduinoTimers_h
#define ArduinoTimers_h
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
#include "ATMEGA2560/Timer.h"
#elif defined(ARDUINO_AVR_UNO)
#include "ATMEGA328/Timer.h"
#else
#error "Cannot compile - ArduinoTimers library does not support your board, or you are missing compatible build flags."
#endif
#endif

View File

@ -1,15 +1,49 @@
//////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////
// © 2020, Chris Harlow. All rights reserved. // DCC-EX CommandStation-EX Please see https://DCC-EX.com
// //
// This file is a demonstattion of setting up a DCC-EX // This file is the main sketch for the Command Station.
// Command station with optional support for direct connection of WiThrottle devices //
// such as "Engine Driver". If you contriol your layout through JMRI // CONFIGURATION:
// then DON'T connect throttles to this wifi, connect them to JMRI. // Configuration is normally performed by editing a file called config.h.
// This file is NOT shipped with the code so that if you pull a later version
// of the code, your configuration will not be overwritten.
// //
// THE WIFI FEATURE IS NOT SUPPORTED ON ARDUINO DEVICES WITH ONLY 2KB RAM. // If you used the automatic installer program, config.h will have been created automatically.
//
// To obtain a starting copy of config.h please copy the file config.example.h which is
// shipped with the code and may be updated as new features are added.
//
// If config.h is not found, config.example.h will be used with all defaults.
//////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////
#include "config.h" #if __has_include ( "config.h")
#include "config.h"
#else
#warning config.h not found. Using defaults from config.example.h
#include "config.example.h"
#endif
/*
* © 2020,2021 Chris Harlow, Harald Barth, David Cutting,
* Fred Decker, Gregor Baues, Anthony W - Dayton All rights reserved.
*
*
* 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 "DCCEX.h" #include "DCCEX.h"
// Create a serial command parser for the USB connection, // Create a serial command parser for the USB connection,
@ -24,10 +58,9 @@ void setup()
// Responsibility 1: Start the usb connection for diagnostics // Responsibility 1: Start the usb connection for diagnostics
// This is normally Serial but uses SerialUSB on a SAMD processor // This is normally Serial but uses SerialUSB on a SAMD processor
Serial.begin(115200); Serial.begin(115200);
DIAG(F("DCC++ EX v%S"),F(VERSION));
CONDITIONAL_LCD_START { CONDITIONAL_LCD_START {
// This block is ignored if LCD not in use // This block is still executed for DIAGS if LCD not in use
LCD(0,F("DCC++ EX v%S"),F(VERSION)); LCD(0,F("DCC++ EX v%S"),F(VERSION));
LCD(1,F("Starting")); LCD(1,F("Starting"));
} }
@ -35,7 +68,7 @@ void setup()
// Start the WiFi interface on a MEGA, Uno cannot currently handle WiFi // Start the WiFi interface on a MEGA, Uno cannot currently handle WiFi
#if WIFI_ON #if WIFI_ON
WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT); WifiInterface::setup(WIFI_SERIAL_LINK_SPEED, F(WIFI_SSID), F(WIFI_PASSWORD), F(WIFI_HOSTNAME), IP_PORT, WIFI_CHANNEL);
#endif // WIFI_ON #endif // WIFI_ON
#if ETHERNET_ON #if ETHERNET_ON
@ -49,9 +82,7 @@ void setup()
// STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorShields.h // STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorShields.h
// Optionally a Timer number (1..4) may be passed to DCC::begin to override the default Timer1 used for the
// waveform generation. e.g. DCC::begin(STANDARD_MOTOR_SHIELD,2); to use timer 2
DCC::begin(MOTOR_SHIELD_TYPE); DCC::begin(MOTOR_SHIELD_TYPE);
#if defined(RMFT_ACTIVE) #if defined(RMFT_ACTIVE)

57
DCC.cpp
View File

@ -17,12 +17,13 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
#include "DIAG.h"
#include "DCC.h" #include "DCC.h"
#include "DCCWaveform.h" #include "DCCWaveform.h"
#include "DIAG.h"
#include "EEStore.h" #include "EEStore.h"
#include "GITHUB_SHA.h" #include "GITHUB_SHA.h"
#include "version.h" #include "version.h"
#include "FSH.h"
// This module is responsible for converting API calls into // This module is responsible for converting API calls into
// messages to be sent to the waveform generator. // messages to be sent to the waveform generator.
@ -43,17 +44,24 @@ const byte FN_GROUP_3=0x04;
const byte FN_GROUP_4=0x08; const byte FN_GROUP_4=0x08;
const byte FN_GROUP_5=0x10; const byte FN_GROUP_5=0x10;
__FlashStringHelper* DCC::shieldName=NULL; FSH* DCC::shieldName=NULL;
byte DCC::joinRelay=UNUSED_PIN;
void DCC::begin(const __FlashStringHelper* motorShieldName, MotorDriver * mainDriver, MotorDriver* progDriver, byte timerNumber) { void DCC::begin(const FSH * motorShieldName, MotorDriver * mainDriver, MotorDriver* progDriver,
shieldName=(__FlashStringHelper*)motorShieldName; byte joinRelayPin) {
shieldName=(FSH *)motorShieldName;
DIAG(F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA)); DIAG(F("<iDCC-EX V-%S / %S / %S G-%S>\n"), F(VERSION), F(ARDUINO_TYPE), shieldName, F(GITHUB_SHA));
joinRelay=joinRelayPin;
if (joinRelay!=UNUSED_PIN) {
pinMode(joinRelay,OUTPUT);
digitalWrite(joinRelay,LOW); // high is relay disengaged
}
// Load stuff from EEprom // Load stuff from EEprom
(void)EEPROM; // tell compiler not to warn this is unused (void)EEPROM; // tell compiler not to warn this is unused
EEStore::init(); EEStore::init();
DCCWaveform::begin(mainDriver,progDriver, timerNumber); DCCWaveform::begin(mainDriver,progDriver);
} }
void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) { void DCC::setThrottle( uint16_t cab, uint8_t tSpeed, bool tDirection) {
@ -222,24 +230,25 @@ void DCC::writeCVBitMain(int cab, int cv, byte bNum, bool bValue) {
} }
void DCC::setProgTrackSyncMain(bool on) { void DCC::setProgTrackSyncMain(bool on) {
if (joinRelay!=UNUSED_PIN) digitalWrite(joinRelay,on?HIGH:LOW);
DCCWaveform::progTrackSyncMain=on; DCCWaveform::progTrackSyncMain=on;
} }
void DCC::setProgTrackBoost(bool on) { void DCC::setProgTrackBoost(bool on) {
DCCWaveform::progTrackBoosted=on; DCCWaveform::progTrackBoosted=on;
} }
__FlashStringHelper* DCC::getMotorShieldName() { FSH* DCC::getMotorShieldName() {
return shieldName; return shieldName;
} }
const ackOp PROGMEM WRITE_BIT0_PROG[] = { const ackOp FLASH WRITE_BIT0_PROG[] = {
BASELINE, BASELINE,
W0,WACK, W0,WACK,
V0, WACK, // validate bit is 0 V0, WACK, // validate bit is 0
ITC1, // if acked, callback(1) ITC1, // if acked, callback(1)
FAIL // callback (-1) FAIL // callback (-1)
}; };
const ackOp PROGMEM WRITE_BIT1_PROG[] = { const ackOp FLASH WRITE_BIT1_PROG[] = {
BASELINE, BASELINE,
W1,WACK, W1,WACK,
V1, WACK, // validate bit is 1 V1, WACK, // validate bit is 1
@ -247,7 +256,7 @@ const ackOp PROGMEM WRITE_BIT1_PROG[] = {
FAIL // callback (-1) FAIL // callback (-1)
}; };
const ackOp PROGMEM VERIFY_BIT0_PROG[] = { const ackOp FLASH VERIFY_BIT0_PROG[] = {
BASELINE, BASELINE,
V0, WACK, // validate bit is 0 V0, WACK, // validate bit is 0
ITC0, // if acked, callback(0) ITC0, // if acked, callback(0)
@ -255,7 +264,7 @@ const ackOp PROGMEM VERIFY_BIT0_PROG[] = {
ITC1, ITC1,
FAIL // callback (-1) FAIL // callback (-1)
}; };
const ackOp PROGMEM VERIFY_BIT1_PROG[] = { const ackOp FLASH VERIFY_BIT1_PROG[] = {
BASELINE, BASELINE,
V1, WACK, // validate bit is 1 V1, WACK, // validate bit is 1
ITC1, // if acked, callback(1) ITC1, // if acked, callback(1)
@ -264,7 +273,7 @@ const ackOp PROGMEM VERIFY_BIT1_PROG[] = {
FAIL // callback (-1) FAIL // callback (-1)
}; };
const ackOp PROGMEM READ_BIT_PROG[] = { const ackOp FLASH READ_BIT_PROG[] = {
BASELINE, BASELINE,
V1, WACK, // validate bit is 1 V1, WACK, // validate bit is 1
ITC1, // if acked, callback(1) ITC1, // if acked, callback(1)
@ -273,7 +282,7 @@ const ackOp PROGMEM READ_BIT_PROG[] = {
FAIL // bit not readable FAIL // bit not readable
}; };
const ackOp PROGMEM WRITE_BYTE_PROG[] = { const ackOp FLASH WRITE_BYTE_PROG[] = {
BASELINE, BASELINE,
WB,WACK, // Write WB,WACK, // Write
VB,WACK, // validate byte VB,WACK, // validate byte
@ -281,7 +290,7 @@ const ackOp PROGMEM WRITE_BYTE_PROG[] = {
FAIL // callback (-1) FAIL // callback (-1)
}; };
const ackOp PROGMEM VERIFY_BYTE_PROG[] = { const ackOp FLASH VERIFY_BYTE_PROG[] = {
BASELINE, BASELINE,
VB,WACK, // validate byte VB,WACK, // validate byte
ITCB, // if ok callback value ITCB, // if ok callback value
@ -306,7 +315,7 @@ const ackOp PROGMEM VERIFY_BYTE_PROG[] = {
FAIL }; FAIL };
const ackOp PROGMEM READ_CV_PROG[] = { const ackOp FLASH READ_CV_PROG[] = {
BASELINE, BASELINE,
STARTMERGE, //clear bit and byte values ready for merge pass STARTMERGE, //clear bit and byte values ready for merge pass
// each bit is validated against 0 and the result inverted in MERGE // each bit is validated against 0 and the result inverted in MERGE
@ -329,7 +338,7 @@ const ackOp PROGMEM READ_CV_PROG[] = {
FAIL }; // verification failed FAIL }; // verification failed
const ackOp PROGMEM LOCO_ID_PROG[] = { const ackOp FLASH LOCO_ID_PROG[] = {
BASELINE, BASELINE,
SETCV, (ackOp)1, SETCV, (ackOp)1,
SETBIT, (ackOp)7, SETBIT, (ackOp)7,
@ -399,7 +408,7 @@ const ackOp PROGMEM LOCO_ID_PROG[] = {
FAIL FAIL
}; };
const ackOp PROGMEM SHORT_LOCO_ID_PROG[] = { const ackOp FLASH SHORT_LOCO_ID_PROG[] = {
BASELINE, BASELINE,
SETCV,(ackOp)19, SETCV,(ackOp)19,
SETBYTE, (ackOp)0, SETBYTE, (ackOp)0,
@ -415,7 +424,7 @@ const ackOp PROGMEM SHORT_LOCO_ID_PROG[] = {
FAIL FAIL
}; };
const ackOp PROGMEM LONG_LOCO_ID_PROG[] = { const ackOp FLASH LONG_LOCO_ID_PROG[] = {
BASELINE, BASELINE,
// Clear consist CV 19 // Clear consist CV 19
SETCV,(ackOp)19, SETCV,(ackOp)19,
@ -501,7 +510,7 @@ void DCC::forgetAllLocos() { // removes all speed reminders
byte DCC::loopStatus=0; byte DCC::loopStatus=0;
void DCC::loop() { void DCC::loop() {
DCCWaveform::loop(); // power overload checks DCCWaveform::loop(ackManagerProg!=NULL); // power overload checks
ackManagerLoop(false); // maintain prog track ack manager ackManagerLoop(false); // maintain prog track ack manager
issueReminders(); issueReminders();
} }
@ -659,7 +668,7 @@ bool DCC::checkResets(bool blocking, uint8_t numResets) {
void DCC::ackManagerLoop(bool blocking) { void DCC::ackManagerLoop(bool blocking) {
while (ackManagerProg) { while (ackManagerProg) {
byte opcode=pgm_read_byte_near(ackManagerProg); byte opcode=GETFLASH(ackManagerProg);
// breaks from this switch will step to next prog entry // breaks from this switch will step to next prog entry
// returns from this switch will stay on same entry // returns from this switch will stay on same entry
@ -786,17 +795,17 @@ void DCC::ackManagerLoop(bool blocking) {
case SETBIT: case SETBIT:
ackManagerProg++; ackManagerProg++;
ackManagerBitNum=pgm_read_byte_near(ackManagerProg); ackManagerBitNum=GETFLASH(ackManagerProg);
break; break;
case SETCV: case SETCV:
ackManagerProg++; ackManagerProg++;
ackManagerCv=pgm_read_byte_near(ackManagerProg); ackManagerCv=GETFLASH(ackManagerProg);
break; break;
case SETBYTE: case SETBYTE:
ackManagerProg++; ackManagerProg++;
ackManagerByte=pgm_read_byte_near(ackManagerProg); ackManagerByte=GETFLASH(ackManagerProg);
break; break;
case SETBYTEH: case SETBYTEH:
@ -822,9 +831,7 @@ void DCC::ackManagerLoop(bool blocking) {
// SKIP opcodes until SKIPTARGET found // SKIP opcodes until SKIPTARGET found
while (opcode!=SKIPTARGET) { while (opcode!=SKIPTARGET) {
ackManagerProg++; ackManagerProg++;
opcode=pgm_read_byte_near(ackManagerProg); opcode=GETFLASH(ackManagerProg);
// Jump over second byte of any 2-byte opcodes.
if (opcode==SETBIT || opcode==SETBYTE || opcode==SETCV) ackManagerProg++;
} }
break; break;
case SKIPTARGET: case SKIPTARGET:

14
DCC.h
View File

@ -21,10 +21,10 @@
#include <Arduino.h> #include <Arduino.h>
#include "MotorDriver.h" #include "MotorDriver.h"
#include "MotorDrivers.h" #include "MotorDrivers.h"
#include "FSH.h"
typedef void (*ACK_CALLBACK)(int result); typedef void (*ACK_CALLBACK)(int result);
enum ackOp enum ackOp : byte
{ // Program opcodes for the ack Manager { // Program opcodes for the ack Manager
BASELINE, // ensure enough resets sent before starting and obtain baseline current BASELINE, // ensure enough resets sent before starting and obtain baseline current
W0, W0,
@ -64,7 +64,8 @@ const byte MAX_LOCOS = 50;
class DCC class DCC
{ {
public: public:
static void begin(const __FlashStringHelper *motorShieldName, MotorDriver *mainDriver, MotorDriver *progDriver, byte timerNumber = 1); static void begin(const FSH * motorShieldName, MotorDriver *mainDriver, MotorDriver *progDriver,
byte joinRelayPin=UNUSED_PIN);
static void loop(); static void loop();
// Public DCC API functions // Public DCC API functions
@ -99,7 +100,7 @@ public:
static void forgetAllLocos(); // removes all speed reminders static void forgetAllLocos(); // removes all speed reminders
static void displayCabList(Print *stream); static void displayCabList(Print *stream);
static __FlashStringHelper *getMotorShieldName(); static FSH *getMotorShieldName();
private: private:
struct LOCO struct LOCO
@ -109,13 +110,14 @@ private:
byte groupFlags; byte groupFlags;
unsigned long functions; unsigned long functions;
}; };
static byte joinRelay;
static byte loopStatus; static byte loopStatus;
static void setThrottle2(uint16_t cab, uint8_t speedCode); static void setThrottle2(uint16_t cab, uint8_t speedCode);
static void updateLocoReminder(int loco, byte speedCode); static void updateLocoReminder(int loco, byte speedCode);
static void setFunctionInternal(int cab, byte fByte, byte eByte); static void setFunctionInternal(int cab, byte fByte, byte eByte);
static bool issueReminder(int reg); static bool issueReminder(int reg);
static int nextLoco; static int nextLoco;
static __FlashStringHelper *shieldName; static FSH *shieldName;
static LOCO speedTable[MAX_LOCOS]; static LOCO speedTable[MAX_LOCOS];
static byte cv1(byte opcode, int cv); static byte cv1(byte opcode, int cv);
@ -162,6 +164,8 @@ private:
#define ARDUINO_TYPE "NANO" #define ARDUINO_TYPE "NANO"
#elif defined(ARDUINO_AVR_MEGA2560) #elif defined(ARDUINO_AVR_MEGA2560)
#define ARDUINO_TYPE "MEGA" #define ARDUINO_TYPE "MEGA"
#elif defined(ARDUINO_ARCH_MEGAAVR)
#define ARDUINO_TYPE "MEGAAVR"
#else #else
#error CANNOT COMPILE - DCC++ EX ONLY WORKS WITH AN ARDUINO UNO, NANO 328, OR ARDUINO MEGA 1280/2560 #error CANNOT COMPILE - DCC++ EX ONLY WORKS WITH AN ARDUINO UNO, NANO 328, OR ARDUINO MEGA 1280/2560
#endif #endif

View File

@ -52,7 +52,7 @@ const int HASH_KEYWORD_ETHERNET = -30767;
const int HASH_KEYWORD_MAX = 16244; const int HASH_KEYWORD_MAX = 16244;
const int HASH_KEYWORD_MIN = 15978; const int HASH_KEYWORD_MIN = 15978;
int DCCEXParser::stashP[MAX_PARAMS]; int DCCEXParser::stashP[MAX_COMMAND_PARAMS];
bool DCCEXParser::stashBusy; bool DCCEXParser::stashBusy;
Print *DCCEXParser::stashStream = NULL; Print *DCCEXParser::stashStream = NULL;
@ -102,7 +102,7 @@ void DCCEXParser::loop(Stream &stream)
Sensor::checkAll(&stream); // Update and print changes Sensor::checkAll(&stream); // Update and print changes
} }
int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd) int DCCEXParser::splitValues(int result[MAX_COMMAND_PARAMS], const byte *cmd)
{ {
byte state = 1; byte state = 1;
byte parameterCount = 0; byte parameterCount = 0;
@ -111,10 +111,10 @@ int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
bool signNegative = false; bool signNegative = false;
// clear all parameters in case not enough found // clear all parameters in case not enough found
for (int i = 0; i < MAX_PARAMS; i++) for (int i = 0; i < MAX_COMMAND_PARAMS; i++)
result[i] = 0; result[i] = 0;
while (parameterCount < MAX_PARAMS) while (parameterCount < MAX_COMMAND_PARAMS)
{ {
byte hot = *remainingCmd; byte hot = *remainingCmd;
@ -143,6 +143,7 @@ int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
runningValue = 10 * runningValue + (hot - '0'); runningValue = 10 * runningValue + (hot - '0');
break; break;
} }
if (hot >= 'a' && hot <= 'z') hot=hot-'a'+'A'; // uppercase a..z
if (hot >= 'A' && hot <= 'Z') if (hot >= 'A' && hot <= 'Z')
{ {
// Since JMRI got modified to send keywords in some rare cases, we need this // Since JMRI got modified to send keywords in some rare cases, we need this
@ -160,7 +161,7 @@ int DCCEXParser::splitValues(int result[MAX_PARAMS], const byte *cmd)
return parameterCount; return parameterCount;
} }
int DCCEXParser::splitHexValues(int result[MAX_PARAMS], const byte *cmd) int DCCEXParser::splitHexValues(int result[MAX_COMMAND_PARAMS], const byte *cmd)
{ {
byte state = 1; byte state = 1;
byte parameterCount = 0; byte parameterCount = 0;
@ -168,10 +169,10 @@ int DCCEXParser::splitHexValues(int result[MAX_PARAMS], const byte *cmd)
const byte *remainingCmd = cmd + 1; // skips the opcode const byte *remainingCmd = cmd + 1; // skips the opcode
// clear all parameters in case not enough found // clear all parameters in case not enough found
for (int i = 0; i < MAX_PARAMS; i++) for (int i = 0; i < MAX_COMMAND_PARAMS; i++)
result[i] = 0; result[i] = 0;
while (parameterCount < MAX_PARAMS) while (parameterCount < MAX_COMMAND_PARAMS)
{ {
byte hot = *remainingCmd; byte hot = *remainingCmd;
@ -237,7 +238,7 @@ void DCCEXParser::setAtCommandCallback(AT_COMMAND_CALLBACK callback)
} }
// Parse an F() string // Parse an F() string
void DCCEXParser::parse(const __FlashStringHelper * cmd) { void DCCEXParser::parse(const FSH * cmd) {
int size=strlen_P((char *)cmd)+1; int size=strlen_P((char *)cmd)+1;
char buffer[size]; char buffer[size];
strcpy_P(buffer,(char *)cmd); strcpy_P(buffer,(char *)cmd);
@ -250,7 +251,7 @@ void DCCEXParser::parse(Print *stream, byte *com, bool blocking)
(void)EEPROM; // tell compiler not to warn this is unused (void)EEPROM; // tell compiler not to warn this is unused
if (Diag::CMD) if (Diag::CMD)
DIAG(F("\nPARSING:%s\n"), com); DIAG(F("\nPARSING:%s\n"), com);
int p[MAX_PARAMS]; int p[MAX_COMMAND_PARAMS];
while (com[0] == '<' || com[0] == ' ') while (com[0] == '<' || com[0] == ' ')
com++; // strip off any number of < or spaces com++; // strip off any number of < or spaces
byte params = splitValues(p, com); byte params = splitValues(p, com);
@ -314,12 +315,33 @@ void DCCEXParser::parse(Print *stream, byte *com, bool blocking)
return; return;
break; break;
case 'a': // ACCESSORY <a ADDRESS SUBADDRESS ACTIVATE> case 'a': // ACCESSORY <a ADDRESS SUBADDRESS ACTIVATE> or <a LINEARADDRESS ACTIVATE>
if (p[2] != (p[2] & 1)) {
return; int address;
DCC::setAccessory(p[0], p[1], p[2] == 1); byte subaddress;
byte activep;
if (params==2) { // <a LINEARADDRESS ACTIVATE>
address=(p[0] - 1) / 4 + 1;
subaddress=(p[0] - 1) % 4;
activep=1;
}
else if (params==3) { // <a ADDRESS SUBADDRESS ACTIVATE>
address=p[0];
subaddress=p[1];
activep=2;
}
else break; // invalid no of parameters
if (
((address & 0x01FF) != address) // invalid address (limit 9 bits )
|| ((subaddress & 0x03) != subaddress) // invalid subaddress (limit 2 bits )
|| ((p[activep] & 0x01) != p[activep]) // invalid activate 0|1
) break;
DCC::setAccessory(address, subaddress,p[activep]==1);
}
return; return;
case 'T': // TURNOUT <T ...> case 'T': // TURNOUT <T ...>
if (parseT(stream, params, p)) if (parseT(stream, params, p))
return; return;
@ -414,7 +436,8 @@ void DCCEXParser::parse(Print *stream, byte *com, bool blocking)
{ {
POWERMODE mode = opcode == '1' ? POWERMODE::ON : POWERMODE::OFF; POWERMODE mode = opcode == '1' ? POWERMODE::ON : POWERMODE::OFF;
DCC::setProgTrackSyncMain(false); // Only <1 JOIN> will set this on, all others set it off DCC::setProgTrackSyncMain(false); // Only <1 JOIN> will set this on, all others set it off
if (params == 0) if (params == 0 ||
(MotorDriver::commonFaultPin && p[0] != HASH_KEYWORD_JOIN)) // commonFaultPin prevents individual track handling
{ {
DCCWaveform::mainTrack.setPowerMode(mode); DCCWaveform::mainTrack.setPowerMode(mode);
DCCWaveform::progTrack.setPowerMode(mode); DCCWaveform::progTrack.setPowerMode(mode);
@ -732,10 +755,6 @@ bool DCCEXParser::parseD(Print *stream, int params, int p[])
Diag::WITHROTTLE = onOff; Diag::WITHROTTLE = onOff;
return true; return true;
case HASH_KEYWORD_DCC:
DCCWaveform::setDiagnosticSlowWave(params >= 1 && p[1] == HASH_KEYWORD_SLOW);
return true;
case HASH_KEYWORD_PROGBOOST: case HASH_KEYWORD_PROGBOOST:
DCC::setProgTrackBoost(true); DCC::setProgTrackBoost(true);
return true; return true;
@ -752,13 +771,13 @@ bool DCCEXParser::parseD(Print *stream, int params, int p[])
} }
// CALLBACKS must be static // CALLBACKS must be static
bool DCCEXParser::stashCallback(Print *stream, int p[MAX_PARAMS]) bool DCCEXParser::stashCallback(Print *stream, int p[MAX_COMMAND_PARAMS])
{ {
if (stashBusy ) if (stashBusy )
return false; return false;
stashBusy = true; stashBusy = true;
stashStream = stream; stashStream = stream;
memcpy(stashP, p, MAX_PARAMS * sizeof(p[0])); memcpy(stashP, p, MAX_COMMAND_PARAMS * sizeof(p[0]));
return true; return true;
} }
void DCCEXParser::callback_W(int result) void DCCEXParser::callback_W(int result)

View File

@ -19,6 +19,7 @@
#ifndef DCCEXParser_h #ifndef DCCEXParser_h
#define DCCEXParser_h #define DCCEXParser_h
#include <Arduino.h> #include <Arduino.h>
#include "FSH.h"
typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int p[]); typedef void (*FILTER_CALLBACK)(Print * stream, byte & opcode, byte & paramCount, int p[]);
typedef void (*AT_COMMAND_CALLBACK)(const byte * command); typedef void (*AT_COMMAND_CALLBACK)(const byte * command);
@ -28,12 +29,12 @@ struct DCCEXParser
DCCEXParser(); DCCEXParser();
void loop(Stream & stream); void loop(Stream & stream);
void parse(Print * stream, byte * command, bool blocking); void parse(Print * stream, byte * command, bool blocking);
void parse(const __FlashStringHelper * cmd); void parse(const FSH * cmd);
void flush(); void flush();
static void setFilter(FILTER_CALLBACK filter); static void setFilter(FILTER_CALLBACK filter);
static void setRMFTFilter(FILTER_CALLBACK filter); static void setRMFTFilter(FILTER_CALLBACK filter);
static void setAtCommandCallback(AT_COMMAND_CALLBACK filter); static void setAtCommandCallback(AT_COMMAND_CALLBACK filter);
static const int MAX_PARAMS=10; // Must not exceed this static const int MAX_COMMAND_PARAMS=10; // Must not exceed this
private: private:
@ -41,8 +42,8 @@ struct DCCEXParser
byte bufferLength=0; byte bufferLength=0;
bool inCommandPayload=false; bool inCommandPayload=false;
byte buffer[MAX_BUFFER+2]; byte buffer[MAX_BUFFER+2];
int splitValues( int result[MAX_PARAMS], const byte * command); int splitValues( int result[MAX_COMMAND_PARAMS], const byte * command);
int splitHexValues( int result[MAX_PARAMS], const byte * command); int splitHexValues( int result[MAX_COMMAND_PARAMS], const byte * command);
bool parseT(Print * stream, int params, int p[]); bool parseT(Print * stream, int params, int p[]);
bool parseZ(Print * stream, int params, int p[]); bool parseZ(Print * stream, int params, int p[]);
@ -54,8 +55,8 @@ struct DCCEXParser
static bool stashBusy; static bool stashBusy;
static Print * stashStream; static Print * stashStream;
static int stashP[MAX_PARAMS]; static int stashP[MAX_COMMAND_PARAMS];
bool stashCallback(Print * stream, int p[MAX_PARAMS]); bool stashCallback(Print * stream, int p[MAX_COMMAND_PARAMS]);
static void callback_W(int result); static void callback_W(int result);
static void callback_B(int result); static void callback_B(int result);
static void callback_R(int result); static void callback_R(int result);

145
DCCTimer.cpp Normal file
View File

@ -0,0 +1,145 @@
/*
* © 2021, Chris Harlow & David Cutting. All rights reserved.
*
* This file is part of Asbelos DCC API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
/* This timer class is used to manage the single timer required to handle the DCC waveform.
* All timer access comes through this class so that it can be compiled for
* various hardware CPU types.
*
* DCCEX works on a single timer interrupt at a regular 58uS interval.
* The DCCWaveform class generates the signals to the motor shield
* based on this timer.
*
* If the motor drivers are BOTH configured to use the correct 2 pins for the architecture,
* (see isPWMPin() function. )
* then this allows us to use a hardware driven pin switching arrangement which is
* achieved by setting the duty cycle of the NEXT clock interrupt to 0% or 100% depending on
* the required pin state. (see setPWM())
* This is more accurate than the software interrupt but at the expense of
* limiting the choice of available pins.
* Fortunately, a standard motor shield on a Mega uses pins that qualify for PWM...
* Other shields may be jumpered to PWM pins or run directly using the software interrupt.
*
* Because the PWM-based waveform is effectively set half a cycle after the software version,
* it is not acceptable to drive the two tracks on different methiods or it would cause
* problems for <1 JOIN> etc.
*
*/
#include "DCCTimer.h"
const int DCC_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle
const long CLOCK_CYCLES=(F_CPU / 1000000 * DCC_SIGNAL_TIME) >>1;
INTERRUPT_CALLBACK interruptHandler=0;
#ifdef ARDUINO_ARCH_MEGAAVR
// Arduino unoWifi Rev2 and nanoEvery architectire
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
noInterrupts();
ADC0.CTRLC = (ADC0.CTRLC & 0b00110000) | 0b01000011; // speed up analogRead sample time
TCB0.CTRLB = TCB_CNTMODE_INT_gc & ~TCB_CCMPEN_bm; // timer compare mode with output disabled
TCB0.CTRLA = TCB_CLKSEL_CLKDIV2_gc; // 8 MHz ~ 0.125 us
TCB0.CCMP = CLOCK_CYCLES -1; // 1 tick less for timer reset
TCB0.INTFLAGS = TCB_CAPT_bm; // clear interrupt request flag
TCB0.INTCTRL = TCB_CAPT_bm; // Enable the interrupt
TCB0.CNT = 0;
TCB0.CTRLA |= TCB_ENABLE_bm; // start
interrupts();
}
// ISR called by timer interrupt every 58uS
ISR(TCB0_INT_vect){
TCB0.INTFLAGS = TCB_CAPT_bm;
interruptHandler();
}
bool DCCTimer::isPWMPin(byte pin) {
return false; // TODO what are the relevant pins?
}
void DCCTimer::setPWM(byte pin, bool high) {
// TODO what are the relevant pins?
}
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
memcpy(mac,(void *) &SIGROW.SERNUM0,6); // serial number
}
#else
// Arduino nano, uno, mega etc
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define TIMER1_A_PIN 11
#define TIMER1_B_PIN 12
#define TIMER1_C_PIN 13
#else
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#endif
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
interruptHandler=callback;
noInterrupts();
ADCSRA = (ADCSRA & 0b11111000) | 0b00000100; // speed up analogRead sample time
TCCR1A = 0;
ICR1 = CLOCK_CYCLES;
TCNT1 = 0;
TCCR1B = _BV(WGM13) | _BV(CS10); // Mode 8, clock select 1
TIMSK1 = _BV(TOIE1); // Enable Software interrupt
interrupts();
}
// ISR called by timer interrupt every 58uS
ISR(TIMER1_OVF_vect){ interruptHandler(); }
// Alternative pin manipulation via PWM control.
bool DCCTimer::isPWMPin(byte pin) {
return pin==TIMER1_A_PIN
|| pin==TIMER1_B_PIN
#ifdef TIMER1_C_PIN
|| pin==TIMER1_C_PIN
#endif
;
}
void DCCTimer::setPWM(byte pin, bool high) {
if (pin==TIMER1_A_PIN) {
TCCR1A |= _BV(COM1A1);
OCR1A= high?1024:0;
}
else if (pin==TIMER1_B_PIN) {
TCCR1A |= _BV(COM1B1);
OCR1B= high?1024:0;
}
#ifdef TIMER1_C_PIN
else if (pin==TIMER1_C_PIN) {
TCCR1A |= _BV(COM1C1);
OCR1C= high?1024:0;
}
#endif
}
#include <avr/boot.h>
void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
for (byte i=0; i<6; i++) mac[i]=boot_signature_byte_get(0x0E + i);
}
#endif

16
DCCTimer.h Normal file
View File

@ -0,0 +1,16 @@
#ifndef DCCTimer_h
#define DCCTimer_h
#include "Arduino.h"
typedef void (*INTERRUPT_CALLBACK)();
class DCCTimer {
public:
static void begin(INTERRUPT_CALLBACK interrupt);
static void getSimulatedMacAddress(byte mac[6]);
static bool isPWMPin(byte pin);
static void setPWM(byte pin, bool high);
private:
};
#endif

View File

@ -17,13 +17,13 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
#pragma GCC optimize ("-O3")
#include <Arduino.h> #include <Arduino.h>
#include "DCCWaveform.h" #include "DCCWaveform.h"
#include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
const int NORMAL_SIGNAL_TIME=58; // this is the 58uS DCC 1-bit waveform half-cycle
const int SLOW_SIGNAL_TIME=NORMAL_SIGNAL_TIME*512;
DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true); DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false); DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
@ -31,53 +31,51 @@ DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
bool DCCWaveform::progTrackSyncMain=false; bool DCCWaveform::progTrackSyncMain=false;
bool DCCWaveform::progTrackBoosted=false; bool DCCWaveform::progTrackBoosted=false;
VirtualTimer * DCCWaveform::interruptTimer=NULL; int DCCWaveform::progTripValue=0;
void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver, byte timerNumber) { void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
mainTrack.motorDriver=mainDriver; mainTrack.motorDriver=mainDriver;
progTrack.motorDriver=progDriver; progTrack.motorDriver=progDriver;
progTripValue = progDriver->mA2raw(TRIP_CURRENT_PROG); // need only calculate once hence static
mainTrack.setPowerMode(POWERMODE::OFF); mainTrack.setPowerMode(POWERMODE::OFF);
progTrack.setPowerMode(POWERMODE::OFF); progTrack.setPowerMode(POWERMODE::OFF);
switch (timerNumber) { // Fault pin config for odd motor boards (example pololu)
case 1: interruptTimer= &TimerA; break; MotorDriver::commonFaultPin = ((mainDriver->getFaultPin() == progDriver->getFaultPin())
case 2: interruptTimer= &TimerB; break; && (mainDriver->getFaultPin() != UNUSED_PIN));
#ifndef ARDUINO_AVR_UNO // Only use PWM if both pins are PWM capable. Otherwise JOIN does not work
case 3: interruptTimer= &TimerC; break; MotorDriver::usePWM= mainDriver->isPWMCapable() && progDriver->isPWMCapable();
#endif if (MotorDriver::usePWM)
default: DIAG(F("\nWaveform using PWM pins for accuracy."));
DIAG(F("\n\n *** Invalid Timer number %d requested. Only 1..3 valid. DCC will not work.*** \n\n"), timerNumber); else
return; DIAG(F("\nWaveform accuracy limited by signal pin configuration."));
} DCCTimer::begin(DCCWaveform::interruptHandler);
interruptTimer->initialize();
interruptTimer->setPeriod(NORMAL_SIGNAL_TIME); // this is the 58uS DCC 1-bit waveform half-cycle
interruptTimer->attachInterrupt(interruptHandler);
interruptTimer->start();
}
void DCCWaveform::setDiagnosticSlowWave(bool slow) {
interruptTimer->setPeriod(slow? SLOW_SIGNAL_TIME : NORMAL_SIGNAL_TIME);
interruptTimer->start();
DIAG(F("\nDCC SLOW WAVE %S\n"),slow?F("SET. DO NOT ADD LOCOS TO TRACK"):F("RESET"));
} }
void DCCWaveform::loop() { void DCCWaveform::loop(bool ackManagerActive) {
mainTrack.checkPowerOverload(); mainTrack.checkPowerOverload(false);
progTrack.checkPowerOverload(); progTrack.checkPowerOverload(ackManagerActive);
} }
// static //
void DCCWaveform::interruptHandler() { void DCCWaveform::interruptHandler() {
// call the timer edge sensitive actions for progtrack and maintrack // call the timer edge sensitive actions for progtrack and maintrack
bool mainCall2 = mainTrack.interrupt1(); // member functions would be cleaner but have more overhead
bool progCall2 = progTrack.interrupt1(); byte sigMain=signalTransform[mainTrack.state];
byte sigProg=progTrackSyncMain? sigMain : signalTransform[progTrack.state];
// Set the signal state for both tracks
mainTrack.motorDriver->setSignal(sigMain);
progTrack.motorDriver->setSignal(sigProg);
// Move on in the state engine
mainTrack.state=stateTransform[mainTrack.state];
progTrack.state=stateTransform[progTrack.state];
// WAVE_PENDING means we dont yet know what the next bit is
if (mainTrack.state==WAVE_PENDING) mainTrack.interrupt2();
if (progTrack.state==WAVE_PENDING) progTrack.interrupt2();
else if (progTrack.ackPending) progTrack.checkAck();
// call (if necessary) the procs to get the current bits
// these must complete within 50microsecs of the interrupt
// but they are only called ONCE PER BIT TRANSMITTED
// after the rising edge of the signal
if (mainCall2) mainTrack.interrupt2();
if (progCall2) progTrack.interrupt2();
} }
@ -92,13 +90,12 @@ const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) { DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
// establish appropriate pins
isMainTrack = isMain; isMainTrack = isMain;
packetPending = false; packetPending = false;
memcpy(transmitPacket, idlePacket, sizeof(idlePacket)); memcpy(transmitPacket, idlePacket, sizeof(idlePacket));
state = 0; state = WAVE_START;
// The +1 below is to allow the preamble generator to create the stop bit // The +1 below is to allow the preamble generator to create the stop bit
// fpr the previous packet. // for the previous packet.
requiredPreambles = preambleBits+1; requiredPreambles = preambleBits+1;
bytes_sent = 0; bytes_sent = 0;
bits_sent = 0; bits_sent = 0;
@ -112,24 +109,17 @@ POWERMODE DCCWaveform::getPowerMode() {
} }
void DCCWaveform::setPowerMode(POWERMODE mode) { void DCCWaveform::setPowerMode(POWERMODE mode) {
// Prevent power switch on with no timer... Otheruise track will get full power DC and locos will run away.
if (!interruptTimer) return;
powerMode = mode; powerMode = mode;
bool ison = (mode == POWERMODE::ON); bool ison = (mode == POWERMODE::ON);
motorDriver->setPower( ison); motorDriver->setPower( ison);
} }
void DCCWaveform::checkPowerOverload() { void DCCWaveform::checkPowerOverload(bool ackManagerActive) {
static int progTripValue = motorDriver->mA2raw(TRIP_CURRENT_PROG); // need only calculate once, hence static
if (millis() - lastSampleTaken < sampleDelay) return; if (millis() - lastSampleTaken < sampleDelay) return;
lastSampleTaken = millis(); lastSampleTaken = millis();
int tripValue= motorDriver->getRawCurrentTripValue(); int tripValue= motorDriver->getRawCurrentTripValue();
if (!isMainTrack && !ackPending && !progTrackSyncMain && !progTrackBoosted) if (!isMainTrack && !ackManagerActive && !progTrackSyncMain && !progTrackBoosted)
tripValue=progTripValue; tripValue=progTripValue;
switch (powerMode) { switch (powerMode) {
@ -138,8 +128,26 @@ void DCCWaveform::checkPowerOverload() {
break; break;
case POWERMODE::ON: case POWERMODE::ON:
// Check current // Check current
lastCurrent = motorDriver->getCurrentRaw(); lastCurrent=motorDriver->getCurrentRaw();
if (lastCurrent <= tripValue) { if (lastCurrent < 0) {
// We have a fault pin condition to take care of
lastCurrent = -lastCurrent;
setPowerMode(POWERMODE::OVERLOAD); // Turn off, decide later how fast to turn on again
if (MotorDriver::commonFaultPin) {
if (lastCurrent <= tripValue) {
setPowerMode(POWERMODE::ON); // maybe other track
}
// Write this after the fact as we want to turn on as fast as possible
// because we don't know which output actually triggered the fault pin
DIAG(F("\n*** COMMON FAULT PIN ACTIVE - TOGGLED POWER on %S ***\n"), isMainTrack ? F("MAIN") : F("PROG"));
} else {
DIAG(F("\n*** %S FAULT PIN ACTIVE - OVERLOAD ***\n"), isMainTrack ? F("MAIN") : F("PROG"));
if (lastCurrent < tripValue) {
lastCurrent = tripValue; // exaggerate
}
}
}
if (lastCurrent < tripValue) {
sampleDelay = POWER_SAMPLE_ON_WAIT; sampleDelay = POWER_SAMPLE_ON_WAIT;
if(power_good_counter<100) if(power_good_counter<100)
power_good_counter++; power_good_counter++;
@ -149,9 +157,9 @@ void DCCWaveform::checkPowerOverload() {
setPowerMode(POWERMODE::OVERLOAD); setPowerMode(POWERMODE::OVERLOAD);
unsigned int mA=motorDriver->raw2mA(lastCurrent); unsigned int mA=motorDriver->raw2mA(lastCurrent);
unsigned int maxmA=motorDriver->raw2mA(tripValue); unsigned int maxmA=motorDriver->raw2mA(tripValue);
DIAG(F("\n*** %S TRACK POWER OVERLOAD current=%d max=%d offtime=%l ***\n"), isMainTrack ? F("MAIN") : F("PROG"), mA, maxmA, power_sample_overload_wait);
power_good_counter=0; power_good_counter=0;
sampleDelay = power_sample_overload_wait; sampleDelay = power_sample_overload_wait;
DIAG(F("\n*** %S TRACK POWER OVERLOAD current=%d max=%d offtime=%d ***\n"), isMainTrack ? F("MAIN") : F("PROG"), mA, maxmA, sampleDelay);
if (power_sample_overload_wait >= 10000) if (power_sample_overload_wait >= 10000)
power_sample_overload_wait = 10000; power_sample_overload_wait = 10000;
else else
@ -162,77 +170,45 @@ void DCCWaveform::checkPowerOverload() {
// Try setting it back on after the OVERLOAD_WAIT // Try setting it back on after the OVERLOAD_WAIT
setPowerMode(POWERMODE::ON); setPowerMode(POWERMODE::ON);
sampleDelay = POWER_SAMPLE_ON_WAIT; sampleDelay = POWER_SAMPLE_ON_WAIT;
// Debug code....
DIAG(F("\n*** %S TRACK POWER RESET delay=%d ***\n"), isMainTrack ? F("MAIN") : F("PROG"), sampleDelay);
break; break;
default: default:
sampleDelay = 999; // cant get here..meaningless statement to avoid compiler warning. sampleDelay = 999; // cant get here..meaningless statement to avoid compiler warning.
} }
} }
// For each state of the wave nextState=stateTransform[currentState]
const WAVE_STATE DCCWaveform::stateTransform[]={
/* WAVE_START -> */ WAVE_PENDING,
/* WAVE_MID_1 -> */ WAVE_START,
/* WAVE_HIGH_0 -> */ WAVE_MID_0,
/* WAVE_MID_0 -> */ WAVE_LOW_0,
/* WAVE_LOW_0 -> */ WAVE_START,
/* WAVE_PENDING (should not happen) -> */ WAVE_PENDING};
// For each state of the wave, signal pin is HIGH or LOW
const bool DCCWaveform::signalTransform[]={
/* WAVE_START -> */ HIGH,
/* WAVE_MID_1 -> */ LOW,
// process time-edge sensitive part of interrupt /* WAVE_HIGH_0 -> */ HIGH,
// return true if second level required /* WAVE_MID_0 -> */ LOW,
bool DCCWaveform::interrupt1() { /* WAVE_LOW_0 -> */ LOW,
// NOTE: this must consume transmission buffers even if the power is off /* WAVE_PENDING (should not happen) -> */ LOW};
// otherwise can cause hangs in main loop waiting for the pendingBuffer.
switch (state) {
case 0: // start of bit transmission
setSignal(HIGH);
state = 1;
return true; // must call interrupt2 to set currentBit
case 1: // 58us after case 0
if (currentBit) {
setSignal(LOW);
state = 0;
}
else {
setSignal(HIGH); // jitter prevention
state = 2;
}
break;
case 2: // 116us after case 0
setSignal(LOW);
state = 3;
break;
case 3: // finished sending zero bit
setSignal(LOW); // jitter prevention
state = 0;
break;
}
// ACK check is prog track only and will only be checked if
// this is not case(0) which needs relatively expensive packet change code to be called.
if (ackPending) checkAck();
return false;
}
void DCCWaveform::setSignal(bool high) {
if (progTrackSyncMain) {
if (!isMainTrack) return; // ignore PROG track waveform while in sync
// set both tracks to same signal
motorDriver->setSignal(high);
progTrack.motorDriver->setSignal(high);
return;
}
motorDriver->setSignal(high);
}
void DCCWaveform::interrupt2() { void DCCWaveform::interrupt2() {
// set currentBit to be the next bit to be sent. // calculate the next bit to be sent:
// set state WAVE_MID_1 for a 1=bit
// or WAVE_HIGH_0 for a 0 bit.
if (remainingPreambles > 0 ) { if (remainingPreambles > 0 ) {
currentBit = true; state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
remainingPreambles--; remainingPreambles--;
return; return;
} }
// Wave has gone HIGH but what happens next depends on the bit to be transmitted
// beware OF 9-BIT MASK generating a zero to start each byte // beware OF 9-BIT MASK generating a zero to start each byte
currentBit = transmitPacket[bytes_sent] & bitMask[bits_sent]; state=(transmitPacket[bytes_sent] & bitMask[bits_sent])? WAVE_MID_1 : WAVE_HIGH_0;
bits_sent++; bits_sent++;
// If this is the last bit of a byte, prepare for the next byte // If this is the last bit of a byte, prepare for the next byte
@ -252,7 +228,10 @@ void DCCWaveform::interrupt2() {
} }
else if (packetPending) { else if (packetPending) {
// Copy pending packet to transmit packet // Copy pending packet to transmit packet
for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b]; // a fixed length memcpy is faster than a variable length loop for these small lengths
// for (int b = 0; b < pendingLength; b++) transmitPacket[b] = pendingPacket[b];
memcpy( transmitPacket, pendingPacket, sizeof(pendingPacket));
transmitLength = pendingLength; transmitLength = pendingLength;
transmitRepeats = pendingRepeats; transmitRepeats = pendingRepeats;
packetPending = false; packetPending = false;
@ -277,7 +256,7 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
while (packetPending); while (packetPending);
byte checksum = 0; byte checksum = 0;
for (int b = 0; b < byteCount; b++) { for (byte b = 0; b < byteCount; b++) {
checksum ^= buffer[b]; checksum ^= buffer[b];
pendingPacket[b] = buffer[b]; pendingPacket[b] = buffer[b];
} }
@ -288,16 +267,12 @@ void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repea
sentResetsSincePacket=0; sentResetsSincePacket=0;
} }
int DCCWaveform::getLastCurrent() {
return lastCurrent;
}
// Operations applicable to PROG track ONLY. // Operations applicable to PROG track ONLY.
// (yes I know I could have subclassed the main track but...) // (yes I know I could have subclassed the main track but...)
void DCCWaveform::setAckBaseline() { void DCCWaveform::setAckBaseline() {
if (isMainTrack) return; if (isMainTrack) return;
int baseline = motorDriver->getCurrentRaw(); int baseline=motorDriver->getCurrentRaw();
ackThreshold= baseline + motorDriver->mA2raw(ackLimitmA); ackThreshold= baseline + motorDriver->mA2raw(ackLimitmA);
if (Diag::ACK) DIAG(F("\nACK baseline=%d/%dmA Threshold=%d/%dmA Duration: %dus <= pulse <= %dus"), if (Diag::ACK) DIAG(F("\nACK baseline=%d/%dmA Threshold=%d/%dmA Duration: %dus <= pulse <= %dus"),
baseline,motorDriver->raw2mA(baseline), baseline,motorDriver->raw2mA(baseline),
@ -325,18 +300,17 @@ byte DCCWaveform::getAck() {
void DCCWaveform::checkAck() { void DCCWaveform::checkAck() {
// This function operates in interrupt() time so must be fast and can't DIAG // This function operates in interrupt() time so must be fast and can't DIAG
if (sentResetsSincePacket > 6) { //ACK timeout if (sentResetsSincePacket > 6) { //ACK timeout
ackCheckDuration=millis()-ackCheckStart; ackCheckDuration=millis()-ackCheckStart;
ackPending = false; ackPending = false;
return; return;
} }
lastCurrent=motorDriver->getCurrentRaw(); int current=motorDriver->getCurrentRaw();
if (lastCurrent > ackMaxCurrent) ackMaxCurrent=lastCurrent; if (current > ackMaxCurrent) ackMaxCurrent=current;
// An ACK is a pulse lasting between minAckPulseDuration and maxAckPulseDuration uSecs (refer @haba) // An ACK is a pulse lasting between minAckPulseDuration and maxAckPulseDuration uSecs (refer @haba)
if (lastCurrent>ackThreshold) { if (current>ackThreshold) {
if (ackPulseStart==0) ackPulseStart=micros(); // leading edge of pulse detected if (ackPulseStart==0) ackPulseStart=micros(); // leading edge of pulse detected
return; return;
} }

View File

@ -20,7 +20,6 @@
#ifndef DCCWaveform_h #ifndef DCCWaveform_h
#define DCCWaveform_h #define DCCWaveform_h
#include "MotorDriver.h" #include "MotorDriver.h"
#include "ArduinoTimers.h"
// Wait times for power management. Unit: milliseconds // Wait times for power management. Unit: milliseconds
const int POWER_SAMPLE_ON_WAIT = 100; const int POWER_SAMPLE_ON_WAIT = 100;
@ -30,15 +29,18 @@ const int POWER_SAMPLE_OVERLOAD_WAIT = 20;
// Number of preamble bits. // Number of preamble bits.
const int PREAMBLE_BITS_MAIN = 16; const int PREAMBLE_BITS_MAIN = 16;
const int PREAMBLE_BITS_PROG = 22; const int PREAMBLE_BITS_PROG = 22;
const byte MAX_PACKET_SIZE = 5; // NMRA standard exrtended packets
// The WAVE_STATE enum is deliberately numbered because a change of order would be catastrophic
// to the transform array.
enum WAVE_STATE : byte {WAVE_START=0,WAVE_MID_1=1,WAVE_HIGH_0=2,WAVE_MID_0=3,WAVE_LOW_0=4,WAVE_PENDING=5};
const byte MAX_PACKET_SIZE = 12;
// NOTE: static functions are used for the overall controller, then // NOTE: static functions are used for the overall controller, then
// one instance is created for each track. // one instance is created for each track.
enum class POWERMODE { OFF, ON, OVERLOAD }; enum class POWERMODE : byte { OFF, ON, OVERLOAD };
const byte idlePacket[] = {0xFF, 0x00, 0xFF}; const byte idlePacket[] = {0xFF, 0x00, 0xFF};
const byte resetPacket[] = {0x00, 0x00, 0x00}; const byte resetPacket[] = {0x00, 0x00, 0x00};
@ -46,17 +48,15 @@ const byte resetPacket[] = {0x00, 0x00, 0x00};
class DCCWaveform { class DCCWaveform {
public: public:
DCCWaveform( byte preambleBits, bool isMain); DCCWaveform( byte preambleBits, bool isMain);
static void begin(MotorDriver * mainDriver, MotorDriver * progDriver, byte timerNumber); static void begin(MotorDriver * mainDriver, MotorDriver * progDriver);
static void setDiagnosticSlowWave(bool slow); static void loop(bool ackManagerActive);
static void loop();
static DCCWaveform mainTrack; static DCCWaveform mainTrack;
static DCCWaveform progTrack; static DCCWaveform progTrack;
void beginTrack(); void beginTrack();
void setPowerMode(POWERMODE); void setPowerMode(POWERMODE);
POWERMODE getPowerMode(); POWERMODE getPowerMode();
void checkPowerOverload(); void checkPowerOverload(bool ackManagerActive);
int getLastCurrent();
inline int get1024Current() { inline int get1024Current() {
if (powerMode == POWERMODE::ON) if (powerMode == POWERMODE::ON)
return (int)(lastCurrent*(long int)1024/motorDriver->getRawCurrentTripValue()); return (int)(lastCurrent*(long int)1024/motorDriver->getRawCurrentTripValue());
@ -105,12 +105,16 @@ class DCCWaveform {
} }
private: private:
static VirtualTimer * interruptTimer;
// For each state of the wave nextState=stateTransform[currentState]
static const WAVE_STATE stateTransform[6];
// For each state of the wave, signal pin is HIGH or LOW
static const bool signalTransform[6];
static void interruptHandler(); static void interruptHandler();
bool interrupt1();
void interrupt2(); void interrupt2();
void checkAck(); void checkAck();
void setSignal(bool high);
bool isMainTrack; bool isMainTrack;
MotorDriver* motorDriver; MotorDriver* motorDriver;
@ -120,15 +124,14 @@ class DCCWaveform {
byte transmitRepeats; // remaining repeats of transmission byte transmitRepeats; // remaining repeats of transmission
byte remainingPreambles; byte remainingPreambles;
byte requiredPreambles; byte requiredPreambles;
bool currentBit; // bit to be transmitted
byte bits_sent; // 0-8 (yes 9 bits) sent for current byte byte bits_sent; // 0-8 (yes 9 bits) sent for current byte
byte bytes_sent; // number of bytes sent from transmitPacket byte bytes_sent; // number of bytes sent from transmitPacket
byte state; // wave generator state machine WAVE_STATE state; // wave generator state machine
byte pendingPacket[MAX_PACKET_SIZE]; byte pendingPacket[MAX_PACKET_SIZE];
byte pendingLength; byte pendingLength;
byte pendingRepeats; byte pendingRepeats;
int lastCurrent; int lastCurrent;
static int progTripValue;
int maxmA; int maxmA;
int tripmA; int tripmA;

1
DIAG.h
View File

@ -18,6 +18,7 @@
*/ */
#ifndef DIAG_h #ifndef DIAG_h
#define DIAG_h #define DIAG_h
#include "StringFormatter.h" #include "StringFormatter.h"
#define DIAG StringFormatter::diag #define DIAG StringFormatter::diag
#define LCD StringFormatter::lcd #define LCD StringFormatter::lcd

View File

@ -17,13 +17,18 @@
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
* *
*/ */
#if __has_include ( "config.h")
#include "config.h" #include "config.h"
#include "defines.h" // This should be changed to DCCEX.h when possible #else
#warning config.h not found. Using defaults from config.example.h
#include "config.example.h"
#endif
#include "defines.h"
#if ETHERNET_ON == true #if ETHERNET_ON == true
#include "EthernetInterface.h" #include "EthernetInterface.h"
#include "DIAG.h" #include "DIAG.h"
#include "CommandDistributor.h" #include "CommandDistributor.h"
#include "DCCTimer.h"
EthernetInterface * EthernetInterface::singleton=NULL; EthernetInterface * EthernetInterface::singleton=NULL;
/** /**
@ -45,10 +50,15 @@ void EthernetInterface::setup()
*/ */
EthernetInterface::EthernetInterface() EthernetInterface::EthernetInterface()
{ {
byte mac[]=MAC_ADDRESS; byte mac[6];
DCCTimer::getSimulatedMacAddress(mac);
DIAG(F("\n+++++ Ethernet Setup. Simulatd mac="));
for (byte i=0;i<sizeof(mac); i++) {
DIAG(F("%x:"),mac[i]);
}
DIAG(F("\n"));
DIAG(F("\n+++++ Ethernet Setup ")); connected=false;
connected=false;
#ifdef IP_ADDRESS #ifdef IP_ADDRESS
Ethernet.begin(mac, IP_ADDRESS); Ethernet.begin(mac, IP_ADDRESS);
@ -73,11 +83,11 @@ EthernetInterface::EthernetInterface()
IPAddress ip = Ethernet.localIP(); // reassign the obtained ip address IPAddress ip = Ethernet.localIP(); // reassign the obtained ip address
server = new EthernetServer(LISTEN_PORT); // Ethernet Server listening on default port LISTEN_PORT server = new EthernetServer(IP_PORT); // Ethernet Server listening on default port IP_PORT
server->begin(); server->begin();
LCD(4,F("IP: %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]); LCD(4,F("IP: %d.%d.%d.%d"), ip[0], ip[1], ip[2], ip[3]);
LCD(5,F("Port:%d"), LISTEN_PORT); LCD(5,F("Port:%d"), IP_PORT);
outboundRing=new RingStream(OUTBOUND_RING_SIZE); outboundRing=new RingStream(OUTBOUND_RING_SIZE);
} }

View File

@ -22,9 +22,13 @@
#ifndef EthernetInterface_h #ifndef EthernetInterface_h
#define EthernetInterface_h #define EthernetInterface_h
#if __has_include ( "config.h")
#include "config.h"
#else
#warning config.h not found. Using defaults from config.example.h
#include "config.example.h"
#endif
#include "DCCEXParser.h" #include "DCCEXParser.h"
#include "MemStream.h"
#include <Arduino.h> #include <Arduino.h>
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#include <Ethernet.h> #include <Ethernet.h>
@ -34,11 +38,7 @@
* @brief Network Configuration * @brief Network Configuration
* *
*/ */
#ifndef MAC_ADDRESS
#error define MAC_ADDRESS in config.h
#endif
#define LISTEN_PORT 2560 // default listen port for the server
#define MAX_ETH_BUFFER 512 #define MAX_ETH_BUFFER 512
#define OUTBOUND_RING_SIZE 2048 #define OUTBOUND_RING_SIZE 2048

30
FSH.h Normal file
View File

@ -0,0 +1,30 @@
#ifndef FSH_h
#define FSH_h
/* This is an architecture support file to manage the differences
* between the nano/uno.mega and the later nanoEvery, unoWifiRev2 etc
*
* IMPORTANT:
* To maintain portability the main code should NOT contain ANY references
* to the following:
*
* __FlashStringHelper Use FSH instead.
* PROGMEM use FLASH instead
* pgm_read_byte_near use GETFLASH instead.
*
*/
#include <Arduino.h>
#if defined(ARDUINO_ARCH_MEGAAVR)
#ifdef F
#undef F
#endif
#define F(str) (str)
typedef char FSH;
#define GETFLASH(addr) (*(const unsigned char *)(addr))
#define FLASH
#else
typedef __FlashStringHelper FSH;
#define GETFLASH(addr) pgm_read_byte_near(addr)
#define FLASH PROGMEM
#endif
#endif

View File

@ -1 +1 @@
#define GITHUB_SHA "62d1f46" #define GITHUB_SHA "fbb9841"

57
I2CManager.cpp Normal file
View File

@ -0,0 +1,57 @@
/*
* © 2021, Neil McKechnie. 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 "I2CManager.h"
// If not already initialised, initialise I2C (wire).
void I2CManagerClass::begin(void) {
if (!_beginCompleted) {
Wire.begin();
_beginCompleted = true;
}
}
// Set clock speed to the lowest requested one. If none requested,
// the Wire default is 100kHz.
void I2CManagerClass::setClock(uint32_t speed) {
if (speed < _clockSpeed && !_clockSpeedFixed) {
_clockSpeed = speed;
Wire.setClock(_clockSpeed);
}
}
// Force clock speed to that specified. It can then only
// be overridden by calling Wire.setClock directly.
void I2CManagerClass::forceClock(uint32_t speed) {
if (!_clockSpeedFixed) {
_clockSpeed = speed;
_clockSpeedFixed = true;
Wire.setClock(_clockSpeed);
}
}
// Check if specified I2C address is responding.
// Returns 0 if OK, or error code.
uint8_t I2CManagerClass::exists(uint8_t address) {
begin();
Wire.beginTransmission(address);
return Wire.endTransmission();
}
I2CManagerClass I2CManager = I2CManagerClass();

61
I2CManager.h Normal file
View File

@ -0,0 +1,61 @@
/*
* © 2021, Neil McKechnie. 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 I2CManager_h
#define I2CManager_h
#include <Wire.h>
/*
* Helper class to manage access to the I2C 'Wire' subsystem.
*
* Helps to avoid calling Wire.begin() multiple times (which is not)
* entirely benign as it reinitialises).
*
* Also helps to avoid the Wire clock from being set, by another device
* driver, to a speed which is higher than a device supports.
*
* Thirdly, it provides a convenient way to check whether there is a
* device on a particular I2C address.
*/
class I2CManagerClass {
public:
I2CManagerClass() {}
// If not already initialised, initialise I2C (wire).
void begin(void);
// Set clock speed to the lowest requested one.
void setClock(uint32_t speed);
// Force clock speed
void forceClock(uint32_t speed);
// Check if specified I2C address is responding.
uint8_t exists(uint8_t address);
private:
bool _beginCompleted = false;
bool _clockSpeedFixed = false;
uint32_t _clockSpeed = 1000000L; // 1MHz max on Arduino.
};
extern I2CManagerClass I2CManager;
#endif

View File

@ -1,6 +1,6 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
* This is free software: you can redistribute it and/or modify * This is free software: you can redistribute it and/or modify
@ -17,63 +17,145 @@
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
// CAUTION: the device dependent parts of this class are created in the .ini using LCD_Implementation.h // CAUTION: the device dependent parts of this class are created in the .ini
// using LCD_Implementation.h
/* The strategy for drawing the screen is as follows.
* 1) There are up to eight rows of text to be displayed.
* 2) Blank rows of text are ignored.
* 3) If there are more non-blank rows than screen lines,
* then all of the rows are displayed, with the rest of the
* screen being blank.
* 4) If there are fewer non-blank rows than screen lines,
* then a scrolling strategy is adopted so that, on each screen
* refresh, a different subset of the rows is presented.
* 5) On each entry into loop2(), a single operation is sent to the
* screen; this may be a position command or a character for
* display. This spreads the onerous work of updating the screen
* and ensures that other loop() functions in the application are
* not held up significantly. The exception to this is when
* the loop2() function is called with force=true, where
* a screen update is executed to completion. This is normally
* only done during start-up.
* The scroll mode is selected by defining SCROLLMODE as 0, 1 or 2
* in the config.h.
* #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
* #define SCROLLMODE 1 is by page (alternate between pages),
* #define SCROLLMODE 2 is by row (move up 1 row at a time).
*/
#include "LCDDisplay.h" #include "LCDDisplay.h"
void LCDDisplay::clear() { void LCDDisplay::clear() {
clearNative(); clearNative();
for (byte row=0;row<MAX_LCD_ROWS; row++) rowBuffer[row][0]='\0'; for (byte row = 0; row < MAX_LCD_ROWS; row++) rowBuffer[row][0] = '\0';
topRow=-1; // loop2 will fill from row 0 topRow = -1; // loop2 will fill from row 0
} }
void LCDDisplay::setRow(byte line) { void LCDDisplay::setRow(byte line) {
hotRow=line; hotRow = line;
hotCol=0; hotCol = 0;
} }
size_t LCDDisplay::write(uint8_t b) { size_t LCDDisplay::write(uint8_t b) {
if (hotRow>=MAX_LCD_ROWS || hotCol>=MAX_LCD_COLS) return -1; if (hotRow >= MAX_LCD_ROWS || hotCol >= MAX_LCD_COLS) return -1;
rowBuffer[hotRow][hotCol]=b; rowBuffer[hotRow][hotCol] = b;
hotCol++; hotCol++;
rowBuffer[hotRow][hotCol]=0; rowBuffer[hotRow][hotCol] = 0;
return 1; return 1;
} }
void LCDDisplay::loop() { void LCDDisplay::loop() {
if (!lcdDisplay) return; if (!lcdDisplay) return;
lcdDisplay->loop2(false); lcdDisplay->loop2(false);
} }
LCDDisplay* LCDDisplay::loop2(bool force) { LCDDisplay *LCDDisplay::loop2(bool force) {
if ((!force) && (millis() - lastScrollTime)< LCD_SCROLL_TIME) return NULL; unsigned long currentMillis = millis();
lastScrollTime=millis();
clearNative(); if (!force) {
int rowFirst=nextFilledRow(); // See if we're in the time between updates
if (rowFirst<0)return NULL; // No filled rows if ((currentMillis - lastScrollTime) < LCD_SCROLL_TIME)
setRowNative(0); return NULL;
writeNative(rowBuffer[rowFirst]); } else {
for (int slot=1;slot<lcdRows;slot++) { // force full screen update from the beginning.
int rowNext=nextFilledRow(); rowFirst = -1;
if (rowNext==rowFirst){ rowNext = 0;
// we have wrapped around and not filled the screen bufferPointer = 0;
topRow=-1; // start again at first row next time. done = false;
break; slot = 0;
}
do {
if (bufferPointer == 0) {
// Find a line of data to write to the screen.
if (rowFirst < 0) rowFirst = rowNext;
skipBlankRows();
if (!done) {
// Non-blank line found, so copy it.
for (uint8_t i = 0; i < sizeof(buffer); i++)
buffer[i] = rowBuffer[rowNext][i];
} else
buffer[0] = '\0'; // Empty line
setRowNative(slot); // Set position for display
charIndex = 0;
bufferPointer = &buffer[0];
} else {
// Write next character, or a space to erase current position.
char ch = *bufferPointer;
if (ch) {
writeNative(ch);
bufferPointer++;
} else
writeNative(' ');
if (++charIndex >= MAX_LCD_COLS) {
// Screen slot completed, move to next slot on screen
slot++;
bufferPointer = 0;
if (!done) {
moveToNextRow();
skipBlankRows();
}
} }
setRowNative(slot);
writeNative(rowBuffer[rowNext]);
}
displayNative();
return NULL;
}
int LCDDisplay::nextFilledRow() { if (slot >= lcdRows) {
for (int rx=1;rx<=MAX_LCD_ROWS;rx++) { // Last slot finished, reset ready for next screen update.
topRow++; #if SCROLLMODE==2
topRow %= MAX_LCD_ROWS; if (!done) {
if (rowBuffer[topRow][0]) return topRow; // On next refresh, restart one row on from previous start.
} rowNext = rowFirst;
return -1; // No slots filled moveToNextRow();
} skipBlankRows();
}
#endif
done = false;
slot = 0;
rowFirst = -1;
lastScrollTime = currentMillis;
return NULL;
}
}
} while (force);
return NULL;
}
void LCDDisplay::moveToNextRow() {
rowNext = (rowNext + 1) % MAX_LCD_ROWS;
#if SCROLLMODE == 1
// Finished if we've looped back to row 0
if (rowNext == 0) done = true;
#else
// Finished if we're back to the first one shown
if (rowNext == rowFirst) done = true;
#endif
}
void LCDDisplay::skipBlankRows() {
while (!done && rowBuffer[rowNext][0] == 0)
moveToNextRow();
}

View File

@ -1,6 +1,6 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
* This is free software: you can redistribute it and/or modify * This is free software: you can redistribute it and/or modify
@ -20,44 +20,61 @@
#define LCDDisplay_h #define LCDDisplay_h
#include <Arduino.h> #include <Arduino.h>
#if __has_include ( "config.h")
#include "config.h"
#endif
// Allow maximum message length to be overridden from config.h
#if !defined(MAX_MSG_SIZE)
#define MAX_MSG_SIZE 16
#endif
// This class is created in LCDisplay_Implementation.h // This class is created in LCDisplay_Implementation.h
class LCDDisplay : public Print { class LCDDisplay : public Print {
public:
static const int MAX_LCD_ROWS = 8;
static const int MAX_LCD_COLS = MAX_MSG_SIZE;
static const long LCD_SCROLL_TIME = 3000; // 3 seconds
public: static LCDDisplay* lcdDisplay;
static const int MAX_LCD_ROWS=8; LCDDisplay();
static const int MAX_LCD_COLS=16; void interfake(int p1, int p2, int p3);
static const long LCD_SCROLL_TIME=3000; // 3 seconds
static LCDDisplay* lcdDisplay;
LCDDisplay();
void interfake(int p1, int p2, int p3);
// Internally handled functions // Internally handled functions
static void loop(); static void loop();
LCDDisplay* loop2(bool force); LCDDisplay* loop2(bool force);
void setRow(byte line); void setRow(byte line);
void clear(); void clear();
virtual size_t write(uint8_t b); virtual size_t write(uint8_t b);
using Print::write; using Print::write;
private: private:
int nextFilledRow(); void moveToNextRow();
void skipBlankRows();
// Relay functions to the live driver
void clearNative(); // Relay functions to the live driver
void displayNative(); void clearNative();
void setRowNative(byte line); void displayNative();
void writeNative(char * b); void setRowNative(byte line);
void writeNative(char b);
unsigned long lastScrollTime=0;
int hotRow=0; unsigned long lastScrollTime = 0;
int hotCol=0; int8_t hotRow = 0;
int topRow=0; int8_t hotCol = 0;
int lcdRows; int8_t topRow = 0;
void renderRow(byte row); uint8_t lcdRows;
char rowBuffer[MAX_LCD_ROWS][MAX_LCD_COLS+1]; uint8_t lcdCols;
int8_t slot = 0;
int8_t rowFirst = -1;
int8_t rowNext = 0;
int8_t charIndex = 0;
char buffer[MAX_LCD_COLS + 1];
char* bufferPointer = 0;
bool done = false;
char rowBuffer[MAX_LCD_ROWS][MAX_LCD_COLS + 1];
}; };
#endif #endif

View File

@ -1,5 +1,5 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
@ -22,12 +22,11 @@
// //
// It will create a driver implemntation and a shim class implementation. // It will create a driver implemntation and a shim class implementation.
// This means that other classes can reference the shim without knowing // This means that other classes can reference the shim without knowing
// which libraray is involved. // which library is involved.
//////////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////////
#ifndef LCD_Implementation_h #ifndef LCD_Implementation_h
#define LCD_Implementation_h #define LCD_Implementation_h
#include "config.h"
#include <Wire.h> #include <Wire.h>
#include "LCDDisplay.h" #include "LCDDisplay.h"
@ -50,7 +49,7 @@ LCDDisplay * LCDDisplay::lcdDisplay=0;
#else #else
#include "LCD_NONE.h" #include "LCD_NONE.h"
#define CONDITIONAL_LCD_START if (false) /* NO LCD CONFIG */ #define CONDITIONAL_LCD_START if (true) /* NO LCD CONFIG, but do the LCD macros to get DIAGS */
#endif #endif
#endif // LCD_Implementation_h #endif // LCD_Implementation_h

View File

@ -1,5 +1,5 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
@ -16,7 +16,7 @@
* You should have received a copy of the GNU General Public License * You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
#include <LiquidCrystal_I2C.h> #include "LiquidCrystal_I2C.h"
LiquidCrystal_I2C LCDDriver(LCD_DRIVER); // set the LCD address, cols, rows LiquidCrystal_I2C LCDDriver(LCD_DRIVER); // set the LCD address, cols, rows
// DEVICE SPECIFIC LCDDisplay Implementation for LCD_DRIVER // DEVICE SPECIFIC LCDDisplay Implementation for LCD_DRIVER
LCDDisplay::LCDDisplay() { LCDDisplay::LCDDisplay() {
@ -28,10 +28,6 @@
} }
void LCDDisplay::interfake(int p1, int p2, int p3) {(void)p1; (void)p2; lcdRows=p3; } void LCDDisplay::interfake(int p1, int p2, int p3) {(void)p1; (void)p2; lcdRows=p3; }
void LCDDisplay::clearNative() {LCDDriver.clear();} void LCDDisplay::clearNative() {LCDDriver.clear();}
void LCDDisplay::setRowNative(byte row) { void LCDDisplay::setRowNative(byte row) { LCDDriver.setCursor(0, row); }
LCDDriver.setCursor(0, row); void LCDDisplay::writeNative(char b){ LCDDriver.write(b); }
LCDDriver.print(F(" "));
LCDDriver.setCursor(0, row);
}
void LCDDisplay::writeNative(char * b){ LCDDriver.print(b); }
void LCDDisplay::displayNative() { LCDDriver.display(); } void LCDDisplay::displayNative() { LCDDriver.display(); }

View File

@ -1,5 +1,5 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
@ -22,6 +22,6 @@
void LCDDisplay::interfake(int p1, int p2, int p3) {(void)p1; (void)p2; (void)p3;} void LCDDisplay::interfake(int p1, int p2, int p3) {(void)p1; (void)p2; (void)p3;}
void LCDDisplay::setRowNative(byte row) { (void)row;} void LCDDisplay::setRowNative(byte row) { (void)row;}
void LCDDisplay::clearNative() {} void LCDDisplay::clearNative() {}
void LCDDisplay::writeNative(char * b){ (void)b;} // void LCDDisplay::writeNative(char b){ (void)b;} //
void LCDDisplay::displayNative(){} void LCDDisplay::displayNative(){}

View File

@ -1,6 +1,6 @@
/* /*
* © 2020, Chris Harlow. All rights reserved. * © 2021, Chris Harlow, Neil McKechnie. All rights reserved.
* *
* This file is part of CommandStation-EX * This file is part of CommandStation-EX
* *
* This is free software: you can redistribute it and/or modify * This is free software: you can redistribute it and/or modify
@ -17,41 +17,59 @@
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>. * along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
// OLED Implementation of LCDDisplay class // OLED Implementation of LCDDisplay class
// Note: this file is optionally included by LCD_Implenentation.h // Note: this file is optionally included by LCD_Implementation.h
// It is NOT a .cpp file to prevent it being compiled and demanding libraraies even when not needed. // It is NOT a .cpp file to prevent it being compiled and demanding libraries
// even when not needed.
#include <Adafruit_SSD1306.h>
Adafruit_SSD1306 LCDDriver(OLED_DRIVER); #include "I2CManager.h"
#include "SSD1306Ascii.h"
#include "Wire.h"
SSD1306AsciiWire LCDDriver;
// DEVICE SPECIFIC LCDDisplay Implementation for OLED // DEVICE SPECIFIC LCDDisplay Implementation for OLED
LCDDisplay::LCDDisplay() { LCDDisplay::LCDDisplay() {
if(LCDDriver.begin(SSD1306_SWITCHCAPVCC, 0x3C) || LCDDriver.begin(SSD1306_SWITCHCAPVCC, 0x3D)) { // Scan for device on 0x3c and 0x3d.
DIAG(F("\nOLED display found")); I2CManager.begin();
delay(2000); // painful Adafruit splash pants! I2CManager.setClock(400000L); // Set max supported I2C speed
lcdDisplay=this; for (byte address = 0x3c; address <= 0x3d; address++) {
LCDDriver.setTextSize(1); // Normal 1:1 pixel scale byte error = I2CManager.exists(address);
LCDDriver.setTextColor(SSD1306_WHITE); // Draw white text if (!error) {
interfake(OLED_DRIVER,0); // Device found
DIAG(F("\nOLED display found at 0x%x"), address);
interfake(OLED_DRIVER, 0);
const DevType *devType;
if (lcdCols == 132)
devType = &SH1106_128x64; // Actually 132x64 but treated as 128x64
else if (lcdCols == 128 && lcdRows == 4)
devType = &Adafruit128x32;
else
devType = &Adafruit128x64;
LCDDriver.begin(devType, address);
lcdDisplay = this;
LCDDriver.setFont(System5x7); // Normal 1:1 pixel scale, 8 bits high
clear(); clear();
return; return;
}
DIAG(F("\nOLED display not found\n"));
} }
}
DIAG(F("\nOLED display not found\n"));
}
void LCDDisplay::interfake(int p1, int p2, int p3) {(void)p1; lcdRows=p2/8; (void)p3;} void LCDDisplay::interfake(int p1, int p2, int p3) {
lcdCols = p1;
lcdRows = p2 / 8;
(void)p3;
}
void LCDDisplay::clearNative() {LCDDriver.clearDisplay();} void LCDDisplay::clearNative() { LCDDriver.clear(); }
void LCDDisplay::setRowNative(byte row) { void LCDDisplay::setRowNative(byte row) {
// Positions text write to start of row 1..n and clears previous text // Positions text write to start of row 1..n and clears previous text
int y=8*row; int y = row;
LCDDriver.fillRect(0, y, LCDDriver.width(), 8, SSD1306_BLACK); LCDDriver.setCursor(0, y);
LCDDriver.setCursor(0, y); }
}
void LCDDisplay::writeNative(char b) { LCDDriver.write(b); }
void LCDDisplay::writeNative(char * b){ LCDDriver.print(b); }
void LCDDisplay::displayNative() {}
void LCDDisplay::displayNative() { LCDDriver.display(); }

245
LiquidCrystal_I2C.cpp Normal file
View File

@ -0,0 +1,245 @@
/*
* © 2021, Neil McKechnie. All rights reserved.
* Based on the work by DFRobot, Frank de Brabander and Marco Schwartz.
*
* 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 "LiquidCrystal_I2C.h"
#include "I2CManager.h"
#include <inttypes.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#define printIIC(args) Wire.write(args)
inline size_t LiquidCrystal_I2C::write(uint8_t value) {
send(value, Rs);
return 1;
}
#else
#include "WProgram.h"
#define printIIC(args) Wire.send(args)
inline void LiquidCrystal_I2C::write(uint8_t value) { send(value, Rs); }
#endif
#include "Wire.h"
// When the display powers up, it is configured as follows:
//
// 1. Display clear
// 2. Function set:
// DL = 1; 8-bit interface data
// N = 0; 1-line display
// F = 0; 5x8 dot character font
// 3. Display on/off control:
// D = 0; Display off
// C = 0; Cursor off
// B = 0; Blinking off
// 4. Entry mode set:
// I/D = 1; Increment by 1
// S = 0; No shift
//
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
// can't assume that its in that state when a sketch starts (and the
// LiquidCrystal constructor is called).
LiquidCrystal_I2C::LiquidCrystal_I2C(uint8_t lcd_Addr, uint8_t lcd_cols,
uint8_t lcd_rows) {
_Addr = lcd_Addr;
_cols = lcd_cols;
_rows = lcd_rows;
_backlightval = LCD_NOBACKLIGHT;
}
void LiquidCrystal_I2C::init() { init_priv(); }
void LiquidCrystal_I2C::init_priv() {
I2CManager.begin();
I2CManager.setClock(100000L); // PCF8574 is limited to 100kHz.
_displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS;
begin(_cols, _rows);
}
void LiquidCrystal_I2C::begin(uint8_t cols, uint8_t lines) {
if (lines > 1) {
_displayfunction |= LCD_2LINE;
}
_numlines = lines;
(void)cols; // Suppress compiler warning.
// SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION!
// according to datasheet, we need at least 40ms after power rises above 2.7V
// before sending commands. Arduino can turn on way befer 4.5V so we'll allow
// 100 milliseconds after pulling both RS and R/W and backlight pin low
expanderWrite(
_backlightval); // reset expander and turn backlight off (Bit 8 =1)
delay(100);
// put the LCD into 4 bit mode
// this is according to the hitachi HD44780 datasheet
// figure 24, pg 46
// we start in 8bit mode, try to set 4 bit mode
write4bits(0x03 << 4);
delayMicroseconds(4500); // wait min 4.1ms
// second try
write4bits(0x03 << 4);
delayMicroseconds(4500); // wait min 4.1ms
// third go!
write4bits(0x03 << 4);
delayMicroseconds(150);
// finally, set to 4-bit interface
write4bits(0x02 << 4);
// set # lines, font size, etc.
command(LCD_FUNCTIONSET | _displayfunction);
// turn the display on with no cursor or blinking default
_displaycontrol = LCD_DISPLAYON | LCD_CURSOROFF | LCD_BLINKOFF;
display();
// clear it off
clear();
// Initialize to default text direction (for roman languages)
_displaymode = LCD_ENTRYLEFT | LCD_ENTRYSHIFTDECREMENT;
// set the entry mode
command(LCD_ENTRYMODESET | _displaymode);
setCursor(0, 0);
}
/********** high level commands, for the user! */
void LiquidCrystal_I2C::clear() {
command(LCD_CLEARDISPLAY); // clear display, set cursor position to zero
delayMicroseconds(2000); // this command takes 1.52ms
}
void LiquidCrystal_I2C::setCursor(uint8_t col, uint8_t row) {
int row_offsets[] = {0x00, 0x40, 0x14, 0x54};
if (row > _numlines) {
row = _numlines - 1; // we count rows starting w/0
}
command(LCD_SETDDRAMADDR | (col + row_offsets[row]));
}
// Turn the display on/off (quickly)
void LiquidCrystal_I2C::noDisplay() {
_displaycontrol &= ~LCD_DISPLAYON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
void LiquidCrystal_I2C::display() {
_displaycontrol |= LCD_DISPLAYON;
command(LCD_DISPLAYCONTROL | _displaycontrol);
}
// Turn the (optional) backlight off/on
void LiquidCrystal_I2C::noBacklight(void) {
_backlightval = LCD_NOBACKLIGHT;
expanderWrite(0);
}
void LiquidCrystal_I2C::backlight(void) {
_backlightval = LCD_BACKLIGHT;
expanderWrite(0);
}
void LiquidCrystal_I2C::setBacklight(uint8_t new_val) {
if (new_val) {
backlight(); // turn backlight on
} else {
noBacklight(); // turn backlight off
}
}
void LiquidCrystal_I2C::printstr(const char c[]) {
// This function is not identical to the function used for "real" I2C displays
// it's here so the user sketch doesn't have to be changed
print(c);
}
/*********** mid level commands, for sending data/cmds */
inline void LiquidCrystal_I2C::command(uint8_t value) { send(value, 0); }
/************ low level data pushing commands **********/
/* According to the NXP Datasheet for the PCF8574 section 8.2:
* "The master (microcontroller) sends the START condition and slave address
* setting the last bit of the address byte to logic 0 for the write mode.
* The PCF8574/74A acknowledges and the master then sends the data byte for
* P7 to P0 to the port register. As the clock line goes HIGH, the 8-bit
* data is presented on the port lines after it has been acknowledged by the
* PCF8574/74A. [...] The master can then send a STOP or ReSTART condition
* or continue sending data. The number of data bytes that can be sent
* successively is not limited and the previous data is overwritten every
* time a data byte has been sent and acknowledged."
*
* This driver takes advantage of this by sending multiple data bytes in succession
* within a single I2C transmission. With a fast clock rate of 400kHz, the time
* between successive updates of the PCF8574 outputs will be at least 2.5us. With
* the default clock rate of 100kHz the time between updates will be at least 10us.
*
* The LCD controller HD44780, according to its datasheet, needs nominally 37us
* (up to 50us) to execute a command (i.e. write to gdram, reposition, etc.). Each
* command is sent in a separate I2C transmission here. The time taken to end a
* transmission and start another one is a stop bit, a start bit, 8 address bits,
* an ack, 8 data bits and another ack; this is at least 20 bits, i.e. >50us
* at 400kHz and >200us at 100kHz. Therefore, we don't need additional delay.
*/
// write either command or data (8 bits) to the HD44780 as
// a single I2C transmission.
void LiquidCrystal_I2C::send(uint8_t value, uint8_t mode) {
uint8_t highnib = value & 0xf0;
uint8_t lownib = (value << 4) & 0xf0;
// Send both nibbles
Wire.beginTransmission(_Addr);
write4bits(highnib | mode, true);
write4bits(lownib | mode, true);
Wire.endTransmission();
}
// write 4 bits to the HD44780 interface. If inTransmission is false
// then the nibble will be sent in its own I2C transmission.
void LiquidCrystal_I2C::write4bits(uint8_t value, bool inTransmission) {
int _data = (int)value | _backlightval;
if (!inTransmission) Wire.beginTransmission(_Addr);
// Enable must be set/reset for at least 450ns. This is well within the
// I2C clock cycle time of 2.5us at 400kHz. Data is clocked in to the
// HD44780 on the trailing edge of the Enable pin.
printIIC(_data | En);
printIIC(_data);
if (!inTransmission) Wire.endTransmission();
}
// write a byte to the PCF8574 I2C interface
void LiquidCrystal_I2C::expanderWrite(uint8_t value) {
int _data = (int)value | _backlightval;
Wire.beginTransmission(_Addr);
printIIC(_data);
Wire.endTransmission();
}

114
LiquidCrystal_I2C.h Normal file
View File

@ -0,0 +1,114 @@
/*
* © 2021, Neil McKechnie. All rights reserved.
* Based on the work by DFRobot, Frank de Brabander and Marco Schwartz.
*
* 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 LiquidCrystal_I2C_h
#define LiquidCrystal_I2C_h
#include <inttypes.h>
#include "Print.h"
#include <Wire.h>
// commands
#define LCD_CLEARDISPLAY 0x01
#define LCD_RETURNHOME 0x02
#define LCD_ENTRYMODESET 0x04
#define LCD_DISPLAYCONTROL 0x08
#define LCD_CURSORSHIFT 0x10
#define LCD_FUNCTIONSET 0x20
#define LCD_SETCGRAMADDR 0x40
#define LCD_SETDDRAMADDR 0x80
// flags for display entry mode
#define LCD_ENTRYRIGHT 0x00
#define LCD_ENTRYLEFT 0x02
#define LCD_ENTRYSHIFTINCREMENT 0x01
#define LCD_ENTRYSHIFTDECREMENT 0x00
// flags for display on/off control
#define LCD_DISPLAYON 0x04
#define LCD_DISPLAYOFF 0x00
#define LCD_CURSORON 0x02
#define LCD_CURSOROFF 0x00
#define LCD_BLINKON 0x01
#define LCD_BLINKOFF 0x00
// flags for display/cursor shift
#define LCD_DISPLAYMOVE 0x08
#define LCD_CURSORMOVE 0x00
#define LCD_MOVERIGHT 0x04
#define LCD_MOVELEFT 0x00
// flags for function set
#define LCD_8BITMODE 0x10
#define LCD_4BITMODE 0x00
#define LCD_2LINE 0x08
#define LCD_1LINE 0x00
#define LCD_5x10DOTS 0x04
#define LCD_5x8DOTS 0x00
// flags for backlight control
#define LCD_BACKLIGHT 0x08
#define LCD_NOBACKLIGHT 0x00
#define En B00000100 // Enable bit
#define Rw B00000010 // Read/Write bit
#define Rs B00000001 // Register select bit
class LiquidCrystal_I2C : public Print {
public:
LiquidCrystal_I2C(uint8_t lcd_Addr,uint8_t lcd_cols,uint8_t lcd_rows);
void begin(uint8_t cols, uint8_t rows);
void clear();
void noDisplay();
void display();
void noBacklight();
void backlight();
void setCursor(uint8_t, uint8_t);
#if defined(ARDUINO) && ARDUINO >= 100
virtual size_t write(uint8_t);
#else
virtual void write(uint8_t);
#endif
void command(uint8_t);
void init();
void oled_init();
////compatibility API function aliases
void setBacklight(uint8_t new_val); // alias for backlight() and nobacklight()
void printstr(const char[]);
private:
void init_priv();
void send(uint8_t, uint8_t);
void write4bits(uint8_t, bool inTransmission=false);
void expanderWrite(uint8_t);
void pulseEnable(uint8_t);
uint8_t _Addr;
uint8_t _displayfunction;
uint8_t _displaycontrol;
uint8_t _displaymode;
uint8_t _numlines;
uint8_t _cols;
uint8_t _rows;
uint8_t _backlightval;
};
#endif

View File

@ -1,98 +0,0 @@
/*
(c) 2015 Ingo Fischer
buffer serial device
based on Arduino SoftwareSerial
Constructor warning messages fixed by Chris Harlow.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library 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
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "MemStream.h"
MemStream::MemStream(uint8_t *buffer, const uint16_t len, uint16_t content_len, bool allowWrite)
:_buffer(buffer),_len(len), _buffer_overflow(false), _pos_read(0), _allowWrite(allowWrite)
{
if (content_len==0) memset(_buffer, 0, _len);
_pos_write=(content_len>len)? len: content_len;
}
size_t MemStream::write(uint8_t byte) {
if (! _allowWrite) return -1;
if (_pos_write >= _len) {
_buffer_overflow = true;
return 0;
}
_buffer[_pos_write] = byte;
++_pos_write;
return 1;
}
void MemStream::flush() {
memset(_buffer, 0, _len);
_pos_write = 0;
_pos_read = 0;
}
int MemStream::read() {
if (_pos_read >= _len) {
_buffer_overflow = true;
return -1;
}
if (_pos_read >= _pos_write) {
return -1;
}
return _buffer[_pos_read++];
}
int MemStream::peek() {
if (_pos_read >= _len) {
_buffer_overflow = true;
return -1;
}
if (_pos_read >= _pos_write) {
return -1;
}
return _buffer[_pos_read+1];
}
int MemStream::available() {
int ret=_pos_write-_pos_read;
if (ret<0) ret=0;
return ret;
}
void MemStream::setBufferContent(uint8_t *buffer, uint16_t content_len) {
memset(_buffer, 0, _len);
memcpy(_buffer, buffer, content_len);
_buffer_overflow=false;
_pos_write=content_len;
_pos_read=0;
}
void MemStream::setBufferContentFromProgmem(uint8_t *buffer, uint16_t content_len) {
memset(_buffer, 0, _len);
memcpy_P(_buffer, buffer, content_len);
_buffer_overflow=false;
_pos_write=content_len;
_pos_read=0;
}
void MemStream::setBufferContentPosition(uint16_t read_pos, uint16_t write_pos) {
_pos_write=write_pos;
_pos_read=read_pos;
}

View File

@ -1,78 +0,0 @@
/*
(c) 2015 Ingo FIscher
buffer serial device
based on Arduino SoftwareSerial
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library 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
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef MemStream_h
#define MemStream_h
#include <inttypes.h>
#if defined(ARDUINO_ARCH_MEGAAVR)
#include <Arduino.h>
#else
#include <Stream.h>
#endif
#include <avr/pgmspace.h>
class MemStream : public Stream
{
private:
uint8_t *_buffer;
const uint16_t _len;
bool _buffer_overflow;
uint16_t _pos_read;
uint16_t _pos_write;
bool _allowWrite;
public:
// public methods
MemStream(uint8_t *buffer, const uint16_t len, uint16_t content_len = 0, bool allowWrite = true);
~MemStream() {}
operator const uint8_t *() const { return _buffer; }
operator const char *() const { return (const char *)_buffer; }
uint16_t current_length() const { return _pos_write; }
bool listen() { return true; }
void end() {}
bool isListening() { return true; }
bool overflow()
{
bool ret = _buffer_overflow;
_buffer_overflow = false;
return ret;
}
int peek();
virtual size_t write(uint8_t byte);
virtual int read();
virtual int available();
virtual void flush();
void setBufferContent(uint8_t *buffer, uint16_t content_len);
void setBufferContentFromProgmem(uint8_t *buffer, uint16_t content_len);
void setBufferContentPosition(uint16_t read_pos, uint16_t write_pos);
using Print::write;
};
#endif

View File

@ -18,50 +18,73 @@
*/ */
#include <Arduino.h> #include <Arduino.h>
#include "MotorDriver.h" #include "MotorDriver.h"
#include "AnalogReadFast.h" #include "DCCTimer.h"
#include "DIAG.h" #include "DIAG.h"
#define setHIGH(fastpin) *fastpin.inout |= fastpin.maskHIGH
#define setLOW(fastpin) *fastpin.inout &= fastpin.maskLOW
#define isHIGH(fastpin) (*fastpin.inout & fastpin.maskHIGH)
#define isLOW(fastpin) (!isHIGH(fastpin))
bool MotorDriver::usePWM=false;
#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_SAMC) || defined(ARDUINO_ARCH_MEGAAVR) bool MotorDriver::commonFaultPin=false;
#define WritePin digitalWrite
#define ReadPin digitalRead
#else
// use the DIO2 libraray for much faster pin access
#define GPIO2_PREFER_SPEED 1
#include <DIO2.h> // use IDE menu Tools..Manage Libraries to locate and install DIO2
#define WritePin digitalWrite2
#define ReadPin digitalRead2
#endif
MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, MotorDriver::MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin,
byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) { byte current_pin, float sense_factor, unsigned int trip_milliamps, byte fault_pin) {
powerPin=power_pin; powerPin=power_pin;
getFastPin(F("POWER"),powerPin,fastPowerPin);
pinMode(powerPin, OUTPUT);
signalPin=signal_pin; signalPin=signal_pin;
getFastPin(F("SIG"),signalPin,fastSignalPin);
pinMode(signalPin, OUTPUT);
signalPin2=signal_pin2; signalPin2=signal_pin2;
if (signalPin2!=UNUSED_PIN) {
dualSignal=true;
getFastPin(F("SIG2"),signalPin2,fastSignalPin2);
pinMode(signalPin2, OUTPUT);
}
else dualSignal=false;
brakePin=brake_pin; brakePin=brake_pin;
if (brake_pin!=UNUSED_PIN){
invertBrake=brake_pin < 0;
brakePin=invertBrake ? 0-brake_pin : brake_pin;
getFastPin(F("BRAKE"),brakePin,fastBrakePin);
pinMode(brakePin, OUTPUT);
setBrake(false);
}
else brakePin=UNUSED_PIN;
currentPin=current_pin; currentPin=current_pin;
senseFactor=sense_factor; pinMode(currentPin, INPUT);
faultPin=fault_pin; faultPin=fault_pin;
if (faultPin != UNUSED_PIN) {
getFastPin(F("FAULT"),faultPin, 1 /*input*/, fastFaultPin);
pinMode(faultPin, INPUT);
}
senseFactor=sense_factor;
tripMilliamps=trip_milliamps; tripMilliamps=trip_milliamps;
rawCurrentTripValue=(int)(trip_milliamps / sense_factor); rawCurrentTripValue=(int)(trip_milliamps / sense_factor);
pinMode(powerPin, OUTPUT);
pinMode(brakePin < 0 ? -brakePin : brakePin, OUTPUT);
setBrake(false);
pinMode(signalPin, OUTPUT);
if (signalPin2 != UNUSED_PIN) pinMode(signalPin2, OUTPUT);
pinMode(currentPin, INPUT);
if (faultPin != UNUSED_PIN) pinMode(faultPin, INPUT);
} }
bool MotorDriver::isPWMCapable() {
return (!dualSignal) && DCCTimer::isPWMPin(signalPin);
}
void MotorDriver::setPower(bool on) { void MotorDriver::setPower(bool on) {
if (brakePin == -4 && on) { if (on) {
// toggle brake before turning power on - resets overcurrent error // toggle brake before turning power on - resets overcurrent error
// on the Pololu board if brake is wired to ^D2. // on the Pololu board if brake is wired to ^D2.
setBrake(true); setBrake(true);
setBrake(false); setBrake(false);
setHIGH(fastPowerPin);
} }
WritePin(powerPin, on ? HIGH : LOW); else setLOW(fastPowerPin);
} }
// setBrake applies brake if on == true. So to get // setBrake applies brake if on == true. So to get
@ -73,30 +96,40 @@ void MotorDriver::setPower(bool on) {
// compensate for that. // compensate for that.
// //
void MotorDriver::setBrake(bool on) { void MotorDriver::setBrake(bool on) {
bool state = on; if (brakePin == UNUSED_PIN) return;
byte pin = brakePin; if (on ^ invertBrake) setHIGH(fastBrakePin);
if (brakePin < 0) { else setLOW(fastBrakePin);
pin=-pin;
state=!state;
}
WritePin(pin, state ? HIGH : LOW);
//DIAG(F("BrakePin: %d is %d\n"), pin, ReadPin(pin));
} }
void MotorDriver::setSignal( bool high) { void MotorDriver::setSignal( bool high) {
WritePin(signalPin, high ? HIGH : LOW); if (usePWM) {
if (signalPin2 != UNUSED_PIN) WritePin(signalPin2, high ? LOW : HIGH); DCCTimer::setPWM(signalPin,high);
}
else {
if (high) {
setHIGH(fastSignalPin);
if (dualSignal) setLOW(fastSignalPin2);
}
else {
setLOW(fastSignalPin);
if (dualSignal) setHIGH(fastSignalPin2);
}
}
} }
/*
* Return the current reading as pin reading 0 to 1023. If the fault
* pin is activated return a negative current to show active fault pin.
* As there is no -0, ceat a little and return -1 in that case.
*/
int MotorDriver::getCurrentRaw() { int MotorDriver::getCurrentRaw() {
if (faultPin != UNUSED_PIN && ReadPin(faultPin) == LOW && ReadPin(powerPin) == HIGH) int current = analogRead(currentPin);
return (int)(32000/senseFactor); if (faultPin != UNUSED_PIN && isLOW(fastFaultPin) && isHIGH(fastPowerPin))
return (current == 0 ? -1 : -current);
return current;
// IMPORTANT: This function can be called in Interrupt() time within the 56uS timer // IMPORTANT: This function can be called in Interrupt() time within the 56uS timer
// The default analogRead takes ~100uS which is catastrphic // The default analogRead takes ~100uS which is catastrphic
// so analogReadFast is used here. (-2uS) // so DCCTimer has set the sample time to be much faster.
return analogReadFast(currentPin);
} }
unsigned int MotorDriver::raw2mA( int raw) { unsigned int MotorDriver::raw2mA( int raw) {
@ -105,3 +138,15 @@ unsigned int MotorDriver::raw2mA( int raw) {
int MotorDriver::mA2raw( unsigned int mA) { int MotorDriver::mA2raw( unsigned int mA) {
return (int)(mA / senseFactor); return (int)(mA / senseFactor);
} }
void MotorDriver::getFastPin(const FSH* type,int pin, bool input, FASTPIN & result) {
DIAG(F("\nMotorDriver %S Pin=%d,"),type,pin);
uint8_t port = digitalPinToPort(pin);
if (input)
result.inout = portInputRegister(port);
else
result.inout = portOutputRegister(port);
result.maskHIGH = digitalPinToBitMask(pin);
result.maskLOW = ~result.maskHIGH;
DIAG(F(" port=0x%x, inoutpin=0x%x, isinput=%d, mask=0x%x\n"),port, result.inout,input,result.maskHIGH);
}

View File

@ -18,12 +18,20 @@
*/ */
#ifndef MotorDriver_h #ifndef MotorDriver_h
#define MotorDriver_h #define MotorDriver_h
#include "FSH.h"
// Virtualised Motor shield 1-track hardware Interface // Virtualised Motor shield 1-track hardware Interface
#ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h #ifndef UNUSED_PIN // sync define with the one in MotorDrivers.h
#define UNUSED_PIN 127 // inside int8_t #define UNUSED_PIN 127 // inside int8_t
#endif #endif
struct FASTPIN {
volatile uint8_t *inout;
uint8_t maskHIGH;
uint8_t maskLOW;
};
class MotorDriver { class MotorDriver {
public: public:
MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin); MotorDriver(byte power_pin, byte signal_pin, byte signal_pin2, int8_t brake_pin, byte current_pin, float senseFactor, unsigned int tripMilliamps, byte faultPin);
@ -34,12 +42,24 @@ class MotorDriver {
virtual unsigned int raw2mA( int raw); virtual unsigned int raw2mA( int raw);
virtual int mA2raw( unsigned int mA); virtual int mA2raw( unsigned int mA);
inline int getRawCurrentTripValue() { inline int getRawCurrentTripValue() {
return rawCurrentTripValue; return rawCurrentTripValue;
} }
bool isPWMCapable();
static bool usePWM;
static bool commonFaultPin; // This is a stupid motor shield which has only a common fault pin for both outputs
inline byte getFaultPin() {
return faultPin;
}
private: private:
byte powerPin, signalPin, signalPin2, currentPin, faultPin; void getFastPin(const FSH* type,int pin, bool input, FASTPIN & result);
int8_t brakePin; // negative means pin is inverted void getFastPin(const FSH* type,int pin, FASTPIN & result) {
getFastPin(type, pin, 0, result);
}
byte powerPin, signalPin, signalPin2, currentPin, faultPin, brakePin;
FASTPIN fastPowerPin,fastSignalPin, fastSignalPin2, fastBrakePin,fastFaultPin;
bool dualSignal; // true to use signalPin2
bool invertBrake; // brake pin passed as negative means pin is inverted
float senseFactor; float senseFactor;
unsigned int tripMilliamps; unsigned int tripMilliamps;
int rawCurrentTripValue; int rawCurrentTripValue;

View File

@ -1,8 +1,6 @@
#ifndef MotorDrivers_h #ifndef MotorDrivers_h
#define MotorDrivers_h #define MotorDrivers_h
#if defined(ARDUINO_ARCH_MEGAAVR)
#include <Arduino.h> #include <Arduino.h>
#endif
// *** PLEASE NOTE *** THIS FILE IS **NOT** INTENDED TO BE EDITED WHEN CONFIGURING A SYSTEM. // *** PLEASE NOTE *** THIS FILE IS **NOT** INTENDED TO BE EDITED WHEN CONFIGURING A SYSTEM.
// It will be overwritten if the library is updated. // It will be overwritten if the library is updated.
@ -31,8 +29,8 @@
// Pololu Motor Shield // Pololu Motor Shield
#define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \ #define POLOLU_MOTOR_SHIELD F("POLOLU_MOTOR_SHIELD"), \
new MotorDriver( 9, 7, UNUSED_PIN, -4, A0, 18, 3000, 12), \ new MotorDriver( 9, 7, UNUSED_PIN, -4, A0, 18, 3000, 12), \
new MotorDriver(10, 8, UNUSED_PIN, UNUSED_PIN, A1, 18, 3000, UNUSED_PIN) new MotorDriver(10, 8, UNUSED_PIN, UNUSED_PIN, A1, 18, 3000, 12)
// //
// Actually, on the Pololu MC33926 shield the enable lines are tied together on pin 4 and the // Actually, on the Pololu MC33926 shield the enable lines are tied together on pin 4 and the
// pins 9 and 10 work as "inverted brake" but as we turn on and off the tracks individually // pins 9 and 10 work as "inverted brake" but as we turn on and off the tracks individually
@ -40,8 +38,8 @@
// version of the code always will be high. That means this config is not usable for generating // version of the code always will be high. That means this config is not usable for generating
// a railcom cuotout in the future. For that one must wire the second ^D2 to pin 2 and define // a railcom cuotout in the future. For that one must wire the second ^D2 to pin 2 and define
// the motor driver like this: // the motor driver like this:
// new MotorDriver(4, 7, UNUSED_PIN, -9, A0, 18, 3000, 12) // new MotorDriver(4, 7, UNUSED_PIN, -9, A0, 18, 3000, 12)
// new MotorDriver(2, 8, UNUSED_PIN, -10, A1, 18, 3000, UNUSED_PIN) // new MotorDriver(2, 8, UNUSED_PIN, -10, A1, 18, 3000, 12)
// See Pololu dial_mc33926_shield_schematic.pdf and truth table on page 17 of the MC33926 data sheet. // See Pololu dial_mc33926_shield_schematic.pdf and truth table on page 17 of the MC33926 data sheet.
// Firebox Mk1 // Firebox Mk1
@ -59,4 +57,9 @@
new MotorDriver(10, 12, UNUSED_PIN, 9, A0, 2.99, 2000, UNUSED_PIN), \ new MotorDriver(10, 12, UNUSED_PIN, 9, A0, 2.99, 2000, UNUSED_PIN), \
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN) new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
// IBT_2 Motor Board for Main and Arduino Motor Shield for Prog
#define IBT_2_WITH_ARDUINO F("IBT_2_WITH_ARDUINO_SHIELD"), \
new MotorDriver(4, 5, 6, UNUSED_PIN, A5, 41.54, 5000, UNUSED_PIN), \
new MotorDriver(11, 13, UNUSED_PIN, UNUSED_PIN, A1, 2.99, 2000, UNUSED_PIN)
#endif #endif

View File

@ -26,6 +26,7 @@
#include <Wire.h> #include <Wire.h>
#include "PWMServoDriver.h" #include "PWMServoDriver.h"
#include "DIAG.h" #include "DIAG.h"
#include "I2CManager.h"
// REGISTER ADDRESSES // REGISTER ADDRESSES
@ -40,6 +41,7 @@ const byte MODE1_RESTART=0x80; /**< Restart enabled */
const byte PCA9685_I2C_ADDRESS=0x40; /** First PCA9685 I2C Slave Address */ const byte PCA9685_I2C_ADDRESS=0x40; /** First PCA9685 I2C Slave Address */
const float FREQUENCY_OSCILLATOR=25000000.0; /** Accurate enough for our purposes */ const float FREQUENCY_OSCILLATOR=25000000.0; /** Accurate enough for our purposes */
const uint8_t PRESCALE_50HZ = (uint8_t)(((FREQUENCY_OSCILLATOR / (50.0 * 4096.0)) + 0.5) - 1); const uint8_t PRESCALE_50HZ = (uint8_t)(((FREQUENCY_OSCILLATOR / (50.0 * 4096.0)) + 0.5) - 1);
const uint32_t MAX_I2C_SPEED = 1000000L; // PCA9685 rated up to 1MHz I2C clock speed
/*! /*!
* @brief Sets the PWM frequency for a chip to 50Hz for servos * @brief Sets the PWM frequency for a chip to 50Hz for servos
@ -52,13 +54,14 @@ bool PWMServoDriver::setup(int board) {
if (board>3 || (failFlags & (1<<board))) return false; if (board>3 || (failFlags & (1<<board))) return false;
if (setupFlags & (1<<board)) return true; if (setupFlags & (1<<board)) return true;
Wire.begin(); I2CManager.begin();
I2CManager.setClock(MAX_I2C_SPEED);
uint8_t i2caddr=PCA9685_I2C_ADDRESS + board; uint8_t i2caddr=PCA9685_I2C_ADDRESS + board;
// Terst if device is available // Test if device is available
Wire.beginTransmission(i2caddr); byte error = I2CManager.exists(i2caddr);
byte error = Wire.endTransmission(); if (error) {
if (error!=0) {
DIAG(F("\nI2C Servo device 0x%x Not Found %d\n"),i2caddr, error); DIAG(F("\nI2C Servo device 0x%x Not Found %d\n"),i2caddr, error);
failFlags|=1<<board; failFlags|=1<<board;
return false; return false;
@ -98,5 +101,4 @@ void PWMServoDriver::writeRegister(uint8_t i2caddr,uint8_t hardwareRegister, uin
Wire.write(hardwareRegister); Wire.write(hardwareRegister);
Wire.write(d); Wire.write(d);
Wire.endTransmission(); Wire.endTransmission();
delay(5); // allow registers to settle before continuing
} }

172
SSD1306Ascii.cpp Normal file
View File

@ -0,0 +1,172 @@
/* Based on Arduino SSD1306Ascii Library, Copyright (C) 2015 by William Greiman
* Modifications (C) 2021 Neil McKechnie
*
* This Library 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.
*
* This Library 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 the Arduino SSD1306Ascii Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include "SSD1306Ascii.h"
//==============================================================================
// SSD1306Ascii Method Definitions
//------------------------------------------------------------------------------
void SSD1306Ascii::clear() {
clear(0, displayWidth() - 1, 0, displayRows() - 1);
}
//------------------------------------------------------------------------------
void SSD1306Ascii::clear(uint8_t c0, uint8_t c1, uint8_t r0, uint8_t r1) {
// Ensure only rows on display will be cleared.
if (r1 >= displayRows()) r1 = displayRows() - 1;
for (uint8_t r = r0; r <= r1; r++) {
setCursor(c0, r);
for (uint8_t c = c0; c <= c1; c++) ssd1306WriteRamBuf(0);
}
setCursor(c0, r0);
}
//------------------------------------------------------------------------------
void SSD1306Ascii::init(const DevType* dev) {
m_col = 0;
m_row = 0;
#ifdef __AVR__
const uint8_t* table = (const uint8_t*)pgm_read_word(&dev->initcmds);
#else // __AVR__
const uint8_t* table = dev->initcmds;
#endif // __AVR
uint8_t size = readFontByte(&dev->initSize);
m_displayWidth = readFontByte(&dev->lcdWidth);
m_displayHeight = readFontByte(&dev->lcdHeight);
m_colOffset = readFontByte(&dev->colOffset);
for (uint8_t i = 0; i < size; i++) {
ssd1306WriteCmd(readFontByte(table + i));
}
clear();
}
//------------------------------------------------------------------------------
void SSD1306Ascii::setCol(uint8_t col) {
if (col < m_displayWidth) {
m_col = col;
col += m_colOffset;
ssd1306WriteCmd(SSD1306_SETLOWCOLUMN | (col & 0XF));
ssd1306WriteCmd(SSD1306_SETHIGHCOLUMN | (col >> 4));
}
}
//------------------------------------------------------------------------------
void SSD1306Ascii::setContrast(uint8_t value) {
ssd1306WriteCmd(SSD1306_SETCONTRAST);
ssd1306WriteCmd(value);
}
//------------------------------------------------------------------------------
void SSD1306Ascii::setCursor(uint8_t col, uint8_t row) {
setCol(col);
setRow(row);
}
//------------------------------------------------------------------------------
void SSD1306Ascii::setFont(const uint8_t* font) {
m_font = font;
m_fontFirstChar = readFontByte(m_font + FONT_FIRST_CHAR);
m_fontCharCount = readFontByte(m_font + FONT_CHAR_COUNT);
}
//------------------------------------------------------------------------------
void SSD1306Ascii::setRow(uint8_t row) {
if (row < displayRows()) {
m_row = row;
ssd1306WriteCmd(SSD1306_SETSTARTPAGE | m_row);
}
}
//------------------------------------------------------------------------------
void SSD1306Ascii::ssd1306WriteRam(uint8_t c) {
if (m_col < m_displayWidth) {
writeDisplay(c, SSD1306_MODE_RAM);
m_col++;
}
}
//------------------------------------------------------------------------------
void SSD1306Ascii::ssd1306WriteRamBuf(uint8_t c) {
if (m_col < m_displayWidth) {
writeDisplay(c, SSD1306_MODE_RAM_BUF);
m_col++;
}
}
//------------------------------------------------------------------------------
size_t SSD1306Ascii::write(uint8_t ch) {
if (!m_font) {
return 0;
}
const uint8_t* base = m_font + FONT_WIDTH_TABLE;
if (ch < m_fontFirstChar || ch >= (m_fontFirstChar + m_fontCharCount))
return 0;
ch -= m_fontFirstChar;
base += fontWidth * ch;
for (uint8_t c = 0; c < fontWidth; c++) {
uint8_t b = readFontByte(base + c);
ssd1306WriteRamBuf(b);
}
for (uint8_t i = 0; i < letterSpacing; i++) {
ssd1306WriteRamBuf(0);
}
flushDisplay();
return 1;
}
//=============================================================================
// SSD1306AsciiWire method definitions
#define m_oledWire Wire
void SSD1306AsciiWire::begin(const DevType* dev, uint8_t i2cAddr) {
#if OPTIMIZE_I2C
m_nData = 0;
#endif // OPTIMIZE_I2C
m_i2cAddr = i2cAddr;
init(dev);
}
//------------------------------------------------------------------------------
void SSD1306AsciiWire::writeDisplay(uint8_t b, uint8_t mode) {
#if OPTIMIZE_I2C
if (m_nData > 16 || (m_nData && mode == SSD1306_MODE_CMD)) {
m_oledWire.endTransmission();
m_nData = 0;
}
if (m_nData == 0) {
m_oledWire.beginTransmission(m_i2cAddr);
m_oledWire.write(mode == SSD1306_MODE_CMD ? 0X00 : 0X40);
}
m_oledWire.write(b);
if (mode == SSD1306_MODE_RAM_BUF) {
m_nData++;
} else {
m_oledWire.endTransmission();
m_nData = 0;
}
#else // OPTIMIZE_I2C
m_oledWire.beginTransmission(m_i2cAddr);
m_oledWire.write(mode == SSD1306_MODE_CMD ? 0X00 : 0X40);
m_oledWire.write(b);
m_oledWire.endTransmission();
#endif // OPTIMIZE_I2C
}
//------------------------------------------------------------------------------
void SSD1306AsciiWire::flushDisplay() {
#if OPTIMIZE_I2C
if (m_nData) {
m_oledWire.endTransmission();
m_nData = 0;
}
#endif // OPTIMIZE_I2C
}
//------------------------------------------------------------------------------

234
SSD1306Ascii.h Normal file
View File

@ -0,0 +1,234 @@
/* Based on Arduino SSD1306Ascii Library, Copyright (C) 2015 by William Greiman
* Modifications (C) 2021 Neil McKechnie
*
* This Library 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.
*
* This Library 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 the Arduino SSD1306Ascii Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file SSD1306AsciiWire.h
* @brief Class for I2C displays using Wire.
*/
#ifndef SSD1306AsciiWire_h
#define SSD1306AsciiWire_h
#include <Wire.h>
#include "Arduino.h"
#include "LCDDisplay.h"
#include "SSD1306font.h"
#include "SSD1306init.h"
//------------------------------------------------------------------------------
/** SSD1306Ascii version basis */
#define SDD1306_ASCII_VERSION 1.3.0
//------------------------------------------------------------------------------
// Configuration options.
/** Use larger faster I2C code. */
#define OPTIMIZE_I2C 1
//------------------------------------------------------------------------------
// Values for writeDisplay() mode parameter.
/** Write to Command register. */
#define SSD1306_MODE_CMD 0
/** Write one byte to display RAM. */
#define SSD1306_MODE_RAM 1
/** Write to display RAM with possible buffering. */
#define SSD1306_MODE_RAM_BUF 2
//------------------------------------------------------------------------------
/**
* @class SSD1306Ascii
* @brief SSD1306 base class
*/
class SSD1306Ascii : public Print {
public:
using Print::write;
SSD1306Ascii() {}
/**
* @brief Clear the display and set the cursor to (0, 0).
*/
void clear();
/**
* @brief Clear a region of the display.
*
* @param[in] c0 Starting column.
* @param[in] c1 Ending column.
* @param[in] r0 Starting row;
* @param[in] r1 Ending row;
* @note The final cursor position will be (c0, r0).
*/
void clear(uint8_t c0, uint8_t c1, uint8_t r0, uint8_t r1);
/**
* @brief Clear a field of n fieldWidth() characters.
*
* @param[in] col Field start column.
*
* @param[in] row Field start row.
*
* @param[in] n Number of characters in the field.
*
*/
void clearField(uint8_t col, uint8_t row, uint8_t n);
/**
* @brief Clear the display to the end of the current line.
* @note The number of rows cleared will be determined by the height
* of the current font.
* @note The cursor will be returned to the original position.
*/
void clearToEOL();
/**
* @return The current column in pixels.
*/
inline uint8_t col() const { return m_col; }
/**
* @return The display hight in pixels.
*/
inline uint8_t displayHeight() const { return m_displayHeight; }
/**
* @brief Set display to normal or 180 degree remap mode.
*
* @param[in] mode true for normal mode, false for remap mode.
*
* @note Adafruit and many ebay displays use remap mode.
* Use normal mode to rotate these displays 180 degrees.
*/
void displayRemap(bool mode);
/**
* @return The display height in rows with eight pixels to a row.
*/
inline uint8_t displayRows() const { return m_displayHeight / 8; }
/**
* @return The display width in pixels.
*/
inline uint8_t displayWidth() const { return m_displayWidth; }
/**
* @brief Set the cursor position to (0, 0).
*/
inline void home() { setCursor(0, 0); }
/**
* @brief Initialize the display controller.
*
* @param[in] dev A display initialization structure.
*/
void init(const DevType* dev);
/**
* @return the current row number with eight pixels to a row.
*/
inline uint8_t row() const { return m_row; }
/**
* @brief Set the current column number.
*
* @param[in] col The desired column number in pixels.
*/
void setCol(uint8_t col);
/**
* @brief Set the display contrast.
*
* @param[in] value The contrast level in th range 0 to 255.
*/
void setContrast(uint8_t value);
/**
* @brief Set the cursor position.
*
* @param[in] col The column number in pixels.
* @param[in] row the row number in eight pixel rows.
*/
void setCursor(uint8_t col, uint8_t row);
/**
* @brief Set the current font.
*
* @param[in] font Pointer to a font table.
*/
void setFont(const uint8_t* font);
/**
* @brief Set the current row number.
*
* @param[in] row the row number in eight pixel rows.
*/
void setRow(uint8_t row);
/**
* @brief Write a command byte to the display controller.
*
* @param[in] c The command byte.
* @note The byte will immediately be sent to the controller.
*/
inline void ssd1306WriteCmd(uint8_t c) { writeDisplay(c, SSD1306_MODE_CMD); }
/**
* @brief Write a byte to RAM in the display controller.
*
* @param[in] c The data byte.
* @note The byte will immediately be sent to the controller.
*/
void ssd1306WriteRam(uint8_t c);
/**
* @brief Write a byte to RAM in the display controller.
*
* @param[in] c The data byte.
* @note The byte may be buffered until a call to ssd1306WriteCmd
* or ssd1306WriteRam or flushDisplay.
*/
void ssd1306WriteRamBuf(uint8_t c);
/**
* @brief Display a character.
*
* @param[in] c The character to display.
* @return one for success else zero.
*/
size_t write(uint8_t c);
protected:
virtual void writeDisplay(uint8_t b, uint8_t mode) = 0;
virtual void flushDisplay() = 0;
uint8_t m_col; // Cursor column.
uint8_t m_row; // Cursor RAM row.
uint8_t m_displayWidth; // Display width.
uint8_t m_displayHeight; // Display height.
uint8_t m_colOffset; // Column offset RAM to SEG.
const uint8_t* m_font = nullptr; // Current font.
// Only fixed size 5x7 fonts in a 6x8 cell are supported.
const int fontWidth = 5;
const int fontHeight = 7;
const uint8_t letterSpacing = 1;
uint8_t m_fontFirstChar;
uint8_t m_fontCharCount;
};
/**
* @class SSD1306AsciiWire
* @brief Class for I2C displays using Wire.
*/
class SSD1306AsciiWire : public SSD1306Ascii {
public:
/**
* @brief Initialize the display controller.
*
* @param[in] dev A device initialization structure.
* @param[in] i2cAddr The I2C address of the display controller.
*/
void begin(const DevType* dev, uint8_t i2cAddr);
protected:
void writeDisplay(uint8_t b, uint8_t mode);
void flushDisplay();
protected:
uint8_t m_i2cAddr;
#if OPTIMIZE_I2C
uint8_t m_nData;
#endif // OPTIMIZE_I2C
};
#endif // SSD1306AsciiWire_h

180
SSD1306font.h Normal file
View File

@ -0,0 +1,180 @@
/*
*
* System5x7
*
*
* File Name : System5x7.h
* Date : 28 Oct 2008
* Font size in bytes : 470
* Font width : 5
* Font height : 7
* Font first char : 32
* Font last char : 127
* Font used chars : 94
*
* The font data are defined as
*
* struct _FONT_ {
* uint16_t font_Size_in_Bytes_over_all_included_Size_it_self;
* uint8_t font_Width_in_Pixel_for_fixed_drawing;
* uint8_t font_Height_in_Pixel_for_all_characters;
* unit8_t font_First_Char;
* uint8_t font_Char_Count;
*
* uint8_t font_Char_Widths[font_Last_Char - font_First_Char +1];
* // for each character the separate width in pixels,
* // characters < 128 have an implicit virtual right empty row
*
* uint8_t font_data[];
* // bit field of all characters
*/
#ifndef SSD1306font_H
#define SSD1306font_H
#define SYSTEM5x7_WIDTH 5
#define SYSTEM5x7_HEIGHT 7
#ifdef __AVR__
#include <avr/pgmspace.h>
/** declare a font for AVR. */
#define GLCDFONTDECL(_n) static const uint8_t __attribute__((progmem)) _n[]
#define readFontByte(addr) pgm_read_byte(addr)
#else // __AVR__
/** declare a font. */
#define GLCDFONTDECL(_n) static const uint8_t _n[]
/** Fake read from flash. */
#define readFontByte(addr) (*(const unsigned char *)(addr))
#endif // __AVR__
//------------------------------------------------------------------------------
// Font Indices
/** No longer used Big Endian length field. Now indicates font type.
*
* 00 00 (fixed width font with 1 padding pixel on right and below)
*
* 00 01 (fixed width font with no padding pixels)
*/
#define FONT_LENGTH 0
/** Maximum character width. */
#define FONT_WIDTH 2
/** Font hight in pixels */
#define FONT_HEIGHT 3
/** Ascii value of first character */
#define FONT_FIRST_CHAR 4
/** count of characters in font. */
#define FONT_CHAR_COUNT 5
/** Offset to width table. */
#define FONT_WIDTH_TABLE 6
//------------------------------------------------------------------------------
GLCDFONTDECL(System5x7) = {
0x0, 0x0, // size of zero indicates fixed width font,
0x05, // width
0x07, // height
0x20, // first char
0x61, // char count
// Fixed width; char width table not used !!!!
// font data
0x00, 0x00, 0x00, 0x00, 0x00, // (space)
0x00, 0x00, 0x5F, 0x00, 0x00, // !
0x00, 0x07, 0x00, 0x07, 0x00, // "
0x14, 0x7F, 0x14, 0x7F, 0x14, // #
0x24, 0x2A, 0x7F, 0x2A, 0x12, // $
0x23, 0x13, 0x08, 0x64, 0x62, // %
0x36, 0x49, 0x55, 0x22, 0x50, // &
0x00, 0x05, 0x03, 0x00, 0x00, // '
0x00, 0x1C, 0x22, 0x41, 0x00, // (
0x00, 0x41, 0x22, 0x1C, 0x00, // )
0x08, 0x2A, 0x1C, 0x2A, 0x08, // *
0x08, 0x08, 0x3E, 0x08, 0x08, // +
0x00, 0x50, 0x30, 0x00, 0x00, // ,
0x08, 0x08, 0x08, 0x08, 0x08, // -
0x00, 0x60, 0x60, 0x00, 0x00, // .
0x20, 0x10, 0x08, 0x04, 0x02, // /
0x3E, 0x51, 0x49, 0x45, 0x3E, // 0
0x00, 0x42, 0x7F, 0x40, 0x00, // 1
0x42, 0x61, 0x51, 0x49, 0x46, // 2
0x21, 0x41, 0x45, 0x4B, 0x31, // 3
0x18, 0x14, 0x12, 0x7F, 0x10, // 4
0x27, 0x45, 0x45, 0x45, 0x39, // 5
0x3C, 0x4A, 0x49, 0x49, 0x30, // 6
0x01, 0x71, 0x09, 0x05, 0x03, // 7
0x36, 0x49, 0x49, 0x49, 0x36, // 8
0x06, 0x49, 0x49, 0x29, 0x1E, // 9
0x00, 0x36, 0x36, 0x00, 0x00, // :
0x00, 0x56, 0x36, 0x00, 0x00, // ;
0x00, 0x08, 0x14, 0x22, 0x41, // <
0x14, 0x14, 0x14, 0x14, 0x14, // =
0x41, 0x22, 0x14, 0x08, 0x00, // >
0x02, 0x01, 0x51, 0x09, 0x06, // ?
0x32, 0x49, 0x79, 0x41, 0x3E, // @
0x7E, 0x11, 0x11, 0x11, 0x7E, // A
0x7F, 0x49, 0x49, 0x49, 0x36, // B
0x3E, 0x41, 0x41, 0x41, 0x22, // C
0x7F, 0x41, 0x41, 0x22, 0x1C, // D
0x7F, 0x49, 0x49, 0x49, 0x41, // E
0x7F, 0x09, 0x09, 0x01, 0x01, // F
0x3E, 0x41, 0x41, 0x51, 0x32, // G
0x7F, 0x08, 0x08, 0x08, 0x7F, // H
0x00, 0x41, 0x7F, 0x41, 0x00, // I
0x20, 0x40, 0x41, 0x3F, 0x01, // J
0x7F, 0x08, 0x14, 0x22, 0x41, // K
0x7F, 0x40, 0x40, 0x40, 0x40, // L
0x7F, 0x02, 0x04, 0x02, 0x7F, // M
0x7F, 0x04, 0x08, 0x10, 0x7F, // N
0x3E, 0x41, 0x41, 0x41, 0x3E, // O
0x7F, 0x09, 0x09, 0x09, 0x06, // P
0x3E, 0x41, 0x51, 0x21, 0x5E, // Q
0x7F, 0x09, 0x19, 0x29, 0x46, // R
0x46, 0x49, 0x49, 0x49, 0x31, // S
0x01, 0x01, 0x7F, 0x01, 0x01, // T
0x3F, 0x40, 0x40, 0x40, 0x3F, // U
0x1F, 0x20, 0x40, 0x20, 0x1F, // V
0x7F, 0x20, 0x18, 0x20, 0x7F, // W
0x63, 0x14, 0x08, 0x14, 0x63, // X
0x03, 0x04, 0x78, 0x04, 0x03, // Y
0x61, 0x51, 0x49, 0x45, 0x43, // Z
0x00, 0x00, 0x7F, 0x41, 0x41, // [
0x02, 0x04, 0x08, 0x10, 0x20, // "\"
0x41, 0x41, 0x7F, 0x00, 0x00, // ]
0x04, 0x02, 0x01, 0x02, 0x04, // ^
0x40, 0x40, 0x40, 0x40, 0x40, // _
0x00, 0x01, 0x02, 0x04, 0x00, // `
0x20, 0x54, 0x54, 0x54, 0x78, // a
0x7F, 0x48, 0x44, 0x44, 0x38, // b
0x38, 0x44, 0x44, 0x44, 0x20, // c
0x38, 0x44, 0x44, 0x48, 0x7F, // d
0x38, 0x54, 0x54, 0x54, 0x18, // e
0x08, 0x7E, 0x09, 0x01, 0x02, // f
0x08, 0x14, 0x54, 0x54, 0x3C, // g
0x7F, 0x08, 0x04, 0x04, 0x78, // h
0x00, 0x44, 0x7D, 0x40, 0x00, // i
0x20, 0x40, 0x44, 0x3D, 0x00, // j
0x00, 0x7F, 0x10, 0x28, 0x44, // k
0x00, 0x41, 0x7F, 0x40, 0x00, // l
0x7C, 0x04, 0x18, 0x04, 0x78, // m
0x7C, 0x08, 0x04, 0x04, 0x78, // n
0x38, 0x44, 0x44, 0x44, 0x38, // o
0x7C, 0x14, 0x14, 0x14, 0x08, // p
0x08, 0x14, 0x14, 0x18, 0x7C, // q
0x7C, 0x08, 0x04, 0x04, 0x08, // r
0x48, 0x54, 0x54, 0x54, 0x20, // s
0x04, 0x3F, 0x44, 0x40, 0x20, // t
0x3C, 0x40, 0x40, 0x20, 0x7C, // u
0x1C, 0x20, 0x40, 0x20, 0x1C, // v
0x3C, 0x40, 0x30, 0x40, 0x3C, // w
0x44, 0x28, 0x10, 0x28, 0x44, // x
0x0C, 0x50, 0x50, 0x50, 0x3C, // y
0x44, 0x64, 0x54, 0x4C, 0x44, // z
0x00, 0x08, 0x36, 0x41, 0x00, // {
0x00, 0x00, 0x7F, 0x00, 0x00, // |
0x00, 0x41, 0x36, 0x08, 0x00, // }
0x08, 0x08, 0x2A, 0x1C, 0x08, // ->
0x08, 0x1C, 0x2A, 0x08, 0x08, // <-
0x00, 0x06, 0x09, 0x09, 0x06 // degree symbol
};
#endif

204
SSD1306init.h Normal file
View File

@ -0,0 +1,204 @@
/* Based on Arduino SSD1306Ascii Library, Copyright (C) 2015 by William Greiman
* Modifications (C) 2021 Neil McKechnie
*
* This Library 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.
*
* This Library 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 the Arduino SSD1306Ascii Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* @file SSD1306init.h
* @brief Display controller initialization commands.
*/
#ifndef SSD1306init_h
#define SSD1306init_h
//------------------------------------------------------------------------------
#ifndef __AVR__
/** Handle AVR flash addressing. */
#define MEM_TYPE
#else // __AVR__
#define MEM_TYPE __attribute__ ((progmem))
#endif // __AVR__
//------------------------------------------------------------------------------
/** Set Lower Column Start Address for Page Addressing Mode. */
#define SSD1306_SETLOWCOLUMN 0x00
/** Set Higher Column Start Address for Page Addressing Mode. */
#define SSD1306_SETHIGHCOLUMN 0x10
/** Set Memory Addressing Mode. */
#define SSD1306_MEMORYMODE 0x20
/** Set display RAM display start line register from 0 - 63. */
#define SSD1306_SETSTARTLINE 0x40
/** Set Display Contrast to one of 256 steps. */
#define SSD1306_SETCONTRAST 0x81
/** Enable or disable charge pump. Follow with 0X14 enable, 0X10 disable. */
#define SSD1306_CHARGEPUMP 0x8D
/** Set Segment Re-map between data column and the segment driver. */
#define SSD1306_SEGREMAP 0xA0
/** Resume display from GRAM content. */
#define SSD1306_DISPLAYALLON_RESUME 0xA4
/** Force display on regardless of GRAM content. */
#define SSD1306_DISPLAYALLON 0xA5
/** Set Normal Display. */
#define SSD1306_NORMALDISPLAY 0xA6
/** Set Inverse Display. */
#define SSD1306_INVERTDISPLAY 0xA7
/** Set Multiplex Ratio from 16 to 63. */
#define SSD1306_SETMULTIPLEX 0xA8
/** Set Display off. */
#define SSD1306_DISPLAYOFF 0xAE
/** Set Display on. */
#define SSD1306_DISPLAYON 0xAF
/**Set GDDRAM Page Start Address. */
#define SSD1306_SETSTARTPAGE 0XB0
/** Set COM output scan direction normal. */
#define SSD1306_COMSCANINC 0xC0
/** Set COM output scan direction reversed. */
#define SSD1306_COMSCANDEC 0xC8
/** Set Display Offset. */
#define SSD1306_SETDISPLAYOFFSET 0xD3
/** Sets COM signals pin configuration to match the OLED panel layout. */
#define SSD1306_SETCOMPINS 0xDA
/** This command adjusts the VCOMH regulator output. */
#define SSD1306_SETVCOMDETECT 0xDB
/** Set Display Clock Divide Ratio/ Oscillator Frequency. */
#define SSD1306_SETDISPLAYCLOCKDIV 0xD5
/** Set Pre-charge Period */
#define SSD1306_SETPRECHARGE 0xD9
/** Deactivate scroll */
#define SSD1306_DEACTIVATE_SCROLL 0x2E
/** No Operation Command. */
#define SSD1306_NOP 0XE3
//------------------------------------------------------------------------------
/** Set Pump voltage value: (30H~33H) 6.4, 7.4, 8.0 (POR), 9.0. */
#define SH1106_SET_PUMP_VOLTAGE 0X30
/** First byte of set charge pump mode */
#define SH1106_SET_PUMP_MODE 0XAD
/** Second byte charge pump on. */
#define SH1106_PUMP_ON 0X8B
/** Second byte charge pump off. */
#define SH1106_PUMP_OFF 0X8A
//------------------------------------------------------------------------------
/**
* @struct DevType
* @brief Device initialization structure.
*/
struct DevType {
/**
* Pointer to initialization command bytes.
*/
const uint8_t* initcmds;
/**
* Number of initialization bytes.
*/
const uint8_t initSize;
/**
* Width of the diaplay in pixels.
*/
const uint8_t lcdWidth;
/**
* Height of the display in pixels.
*/
const uint8_t lcdHeight;
/**
* Column offset RAM to display. Used to pick start column of SH1106.
*/
const uint8_t colOffset;
};
//------------------------------------------------------------------------------
// this section is based on https://github.com/adafruit/Adafruit_SSD1306
/** Initialization commands for a 128x32 SSD1306 oled display. */
static const uint8_t MEM_TYPE Adafruit128x32init[] = {
// Init sequence for Adafruit 128x32 OLED module
SSD1306_DISPLAYOFF,
SSD1306_SETDISPLAYCLOCKDIV, 0x80, // the suggested ratio 0x80
SSD1306_SETMULTIPLEX, 0x1F, // ratio 32
SSD1306_SETDISPLAYOFFSET, 0x0, // no offset
SSD1306_SETSTARTLINE | 0x0, // line #0
SSD1306_CHARGEPUMP, 0x14, // internal vcc
SSD1306_MEMORYMODE, 0x02, // page mode
SSD1306_SEGREMAP | 0x1, // column 127 mapped to SEG0
SSD1306_COMSCANDEC, // column scan direction reversed
SSD1306_SETCOMPINS, 0x02, // sequential COM pins, disable remap
SSD1306_SETCONTRAST, 0x7F, // contrast level 127
SSD1306_SETPRECHARGE, 0xF1, // pre-charge period (1, 15)
SSD1306_SETVCOMDETECT, 0x40, // vcomh regulator level
SSD1306_DISPLAYALLON_RESUME,
SSD1306_NORMALDISPLAY,
SSD1306_DISPLAYON
};
/** Initialize a 128x32 SSD1306 oled display. */
static const DevType MEM_TYPE Adafruit128x32 = {
Adafruit128x32init,
sizeof(Adafruit128x32init),
128,
32,
0
};
//------------------------------------------------------------------------------
// This section is based on https://github.com/adafruit/Adafruit_SSD1306
/** Initialization commands for a 128x64 SSD1306 oled display. */
static const uint8_t MEM_TYPE Adafruit128x64init[] = {
// Init sequence for Adafruit 128x64 OLED module
SSD1306_DISPLAYOFF,
SSD1306_SETDISPLAYCLOCKDIV, 0x80, // the suggested ratio 0x80
SSD1306_SETMULTIPLEX, 0x3F, // ratio 64
SSD1306_SETDISPLAYOFFSET, 0x0, // no offset
SSD1306_SETSTARTLINE | 0x0, // line #0
SSD1306_CHARGEPUMP, 0x14, // internal vcc
SSD1306_MEMORYMODE, 0x02, // page mode
SSD1306_SEGREMAP | 0x1, // column 127 mapped to SEG0
SSD1306_COMSCANDEC, // column scan direction reversed
SSD1306_SETCOMPINS, 0x12, // alt COM pins, disable remap
SSD1306_SETCONTRAST, 0x7F, // contrast level 127
SSD1306_SETPRECHARGE, 0xF1, // pre-charge period (1, 15)
SSD1306_SETVCOMDETECT, 0x40, // vcomh regulator level
SSD1306_DISPLAYALLON_RESUME,
SSD1306_NORMALDISPLAY,
SSD1306_DISPLAYON
};
/** Initialize a 128x64 oled display. */
static const DevType MEM_TYPE Adafruit128x64 = {
Adafruit128x64init,
sizeof(Adafruit128x64init),
128,
64,
0
};
//------------------------------------------------------------------------------
// This section is based on https://github.com/stanleyhuangyc/MultiLCD
/** Initialization commands for a 128x64 SH1106 oled display. */
static const uint8_t MEM_TYPE SH1106_128x64init[] = {
SSD1306_DISPLAYOFF,
SSD1306_SETSTARTPAGE | 0X0, // set page address
SSD1306_SETCONTRAST, 0x80, // 128
SSD1306_SEGREMAP | 0X1, // set segment remap
SSD1306_NORMALDISPLAY, // normal / reverse
SSD1306_SETMULTIPLEX, 0x3F, // ratio 64
SH1106_SET_PUMP_MODE, SH1106_PUMP_ON, // set charge pump enable
SH1106_SET_PUMP_VOLTAGE | 0X2, // 8.0 volts
SSD1306_COMSCANDEC, // Com scan direction
SSD1306_SETDISPLAYOFFSET, 0X00, // set display offset
SSD1306_SETDISPLAYCLOCKDIV, 0X80, // set osc division
SSD1306_SETPRECHARGE, 0X1F, // set pre-charge period
SSD1306_SETCOMPINS, 0X12, // set COM pins
SSD1306_SETVCOMDETECT, 0x40, // set vcomh
SSD1306_DISPLAYON
};
/** Initialize a 128x64 oled SH1106 display. */
static const DevType MEM_TYPE SH1106_128x64 = {
SH1106_128x64init,
sizeof(SH1106_128x64init),
128,
64,
2 // SH1106 is a 132x64 controller. Use middle 128 columns.
};
#endif // SSD1306init_h

View File

@ -22,13 +22,9 @@
#if defined(ARDUINO_ARCH_SAMD) #if defined(ARDUINO_ARCH_SAMD)
// Some processors use a gcc compiler that renames va_list!!! // Some processors use a gcc compiler that renames va_list!!!
#include <cstdarg> #include <cstdarg>
Print * StringFormatter::diagSerial= &SerialUSB; Print * StringFormatter::diagSerial= &SerialUSB;
#else
#elif defined(ARDUINO_ARCH_AVR)
Print * StringFormatter::diagSerial= &Serial;
#elif defined(ARDUINO_ARCH_MEGAAVR)
Print * StringFormatter::diagSerial=&Serial; Print * StringFormatter::diagSerial=&Serial;
#define __FlashStringHelper char
#endif #endif
#include "LCDDisplay.h" #include "LCDDisplay.h"
@ -40,14 +36,14 @@ bool Diag::WITHROTTLE=false;
bool Diag::ETHERNET=false; bool Diag::ETHERNET=false;
void StringFormatter::diag( const __FlashStringHelper* input...) { void StringFormatter::diag( const FSH* input...) {
if (!diagSerial) return; if (!diagSerial) return;
va_list args; va_list args;
va_start(args, input); va_start(args, input);
send2(diagSerial,input,args); send2(diagSerial,input,args);
} }
void StringFormatter::lcd(byte row, const __FlashStringHelper* input...) { void StringFormatter::lcd(byte row, const FSH* input...) {
va_list args; va_list args;
// Issue the LCD as a diag first // Issue the LCD as a diag first
@ -62,25 +58,25 @@ void StringFormatter::lcd(byte row, const __FlashStringHelper* input...) {
send2(LCDDisplay::lcdDisplay,input,args); send2(LCDDisplay::lcdDisplay,input,args);
} }
void StringFormatter::send(Print * stream, const __FlashStringHelper* input...) { void StringFormatter::send(Print * stream, const FSH* input...) {
va_list args; va_list args;
va_start(args, input); va_start(args, input);
send2(stream,input,args); send2(stream,input,args);
} }
void StringFormatter::send(Print & stream, const __FlashStringHelper* input...) { void StringFormatter::send(Print & stream, const FSH* input...) {
va_list args; va_list args;
va_start(args, input); va_start(args, input);
send2(&stream,input,args); send2(&stream,input,args);
} }
void StringFormatter::send2(Print * stream,const __FlashStringHelper* format, va_list args) { void StringFormatter::send2(Print * stream,const FSH* format, va_list args) {
// thanks to Jan Turoň https://arduino.stackexchange.com/questions/56517/formatting-strings-in-arduino-for-output // thanks to Jan Turoň https://arduino.stackexchange.com/questions/56517/formatting-strings-in-arduino-for-output
char* flash=(char*)format; char* flash=(char*)format;
for(int i=0; ; ++i) { for(int i=0; ; ++i) {
char c=pgm_read_byte_near(flash+i); char c=GETFLASH(flash+i);
if (c=='\0') return; if (c=='\0') return;
if(c!='%') { stream->print(c); continue; } if(c!='%') { stream->print(c); continue; }
@ -91,14 +87,14 @@ void StringFormatter::send2(Print * stream,const __FlashStringHelper* format, va
formatContinues=false; formatContinues=false;
i++; i++;
c=pgm_read_byte_near(flash+i); c=GETFLASH(flash+i);
switch(c) { switch(c) {
case '%': stream->print('%'); break; case '%': stream->print('%'); break;
case 'c': stream->print((char) va_arg(args, int)); break; case 'c': stream->print((char) va_arg(args, int)); break;
case 's': stream->print(va_arg(args, char*)); break; case 's': stream->print(va_arg(args, char*)); break;
case 'e': printEscapes(stream,va_arg(args, char*)); break; case 'e': printEscapes(stream,va_arg(args, char*)); break;
case 'E': printEscapes(stream,(const __FlashStringHelper*)va_arg(args, char*)); break; case 'E': printEscapes(stream,(const FSH*)va_arg(args, char*)); break;
case 'S': stream->print((const __FlashStringHelper*)va_arg(args, char*)); break; case 'S': stream->print((const FSH*)va_arg(args, char*)); break;
case 'd': printPadded(stream,va_arg(args, int), formatWidth, formatLeft); break; case 'd': printPadded(stream,va_arg(args, int), formatWidth, formatLeft); break;
case 'l': printPadded(stream,va_arg(args, long), formatWidth, formatLeft); break; case 'l': printPadded(stream,va_arg(args, long), formatWidth, formatLeft); break;
case 'b': stream->print(va_arg(args, int), BIN); break; case 'b': stream->print(va_arg(args, int), BIN); break;
@ -138,12 +134,12 @@ void StringFormatter::printEscapes(Print * stream,char * input) {
} }
} }
void StringFormatter::printEscapes(Print * stream, const __FlashStringHelper * input) { void StringFormatter::printEscapes(Print * stream, const FSH * input) {
if (!stream) return; if (!stream) return;
char* flash=(char*)input; char* flash=(char*)input;
for(int i=0; ; ++i) { for(int i=0; ; ++i) {
char c=pgm_read_byte_near(flash+i); char c=GETFLASH(flash+i);
printEscape(stream,c); printEscape(stream,c);
if (c=='\0') return; if (c=='\0') return;
} }

View File

@ -19,12 +19,10 @@
#ifndef StringFormatter_h #ifndef StringFormatter_h
#define StringFormatter_h #define StringFormatter_h
#include <Arduino.h> #include <Arduino.h>
#include "FSH.h"
#if defined(ARDUINO_ARCH_SAMD) #if defined(ARDUINO_ARCH_SAMD)
// Some processors use a gcc compiler that renames va_list!!! // Some processors use a gcc compiler that renames va_list!!!
#include <cstdarg> #include <cstdarg>
#elif defined(ARDUINO_ARCH_MEGAAVR)
#define __FlashStringHelper char
#endif #endif
#include "LCDDisplay.h" #include "LCDDisplay.h"
@ -41,22 +39,22 @@ class Diag {
class StringFormatter class StringFormatter
{ {
public: public:
static void send(Print * serial, const __FlashStringHelper* input...); static void send(Print * serial, const FSH* input...);
static void send(Print & serial, const __FlashStringHelper* input...); static void send(Print & serial, const FSH* input...);
static void printEscapes(Print * serial,char * input); static void printEscapes(Print * serial,char * input);
static void printEscapes(Print * serial,const __FlashStringHelper* input); static void printEscapes(Print * serial,const FSH* input);
static void printEscape(Print * serial, char c); static void printEscape(Print * serial, char c);
// DIAG support // DIAG support
static Print * diagSerial; static Print * diagSerial;
static void diag( const __FlashStringHelper* input...); static void diag( const FSH* input...);
static void lcd(byte row, const __FlashStringHelper* input...); static void lcd(byte row, const FSH* input...);
static void printEscapes(char * input); static void printEscapes(char * input);
static void printEscape( char c); static void printEscape( char c);
private: private:
static void send2(Print * serial, const __FlashStringHelper* input,va_list args); static void send2(Print * serial, const FSH* input,va_list args);
static void printPadded(Print* stream, long value, byte width, bool formatLeft); static void printPadded(Print* stream, long value, byte width, bool formatLeft);
}; };

View File

@ -1,52 +0,0 @@
// This file is copied from https://github.com/davidcutting42/ArduinoTimers
// All Credit to David Cutting
#include <Arduino.h>
#if defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560)
#include "ATMEGA2560/Timer.h"
Timer TimerA(1);
Timer TimerB(3);
Timer TimerC(4);
Timer TimerD(5);
ISR(TIMER1_OVF_vect)
{
TimerA.isrCallback();
}
ISR(TIMER3_OVF_vect)
{
TimerB.isrCallback();
}
ISR(TIMER4_OVF_vect)
{
TimerC.isrCallback();
}
ISR(TIMER5_OVF_vect)
{
TimerD.isrCallback();
}
#elif defined(ARDUINO_AVR_UNO) // Todo: add other 328 boards for compatibility
#include "ATMEGA328/Timer.h"
Timer TimerA(1);
Timer TimerB(2);
ISR(TIMER1_OVF_vect)
{
TimerA.isrCallback();
}
ISR(TIMER2_OVF_vect)
{
TimerB.isrCallback();
}
#endif

View File

@ -1,21 +0,0 @@
// This file is copied from https://github.com/davidcutting42/ArduinoTimers
// All Credit to David Cutting
#ifndef VirtualTimer_h
#define VirtualTimer_h
class VirtualTimer
{
public:
virtual void initialize() = 0;
virtual void setPeriod(unsigned long microseconds) = 0;
virtual void start() = 0;
virtual void stop() = 0;
virtual void attachInterrupt(void (*isr)()) = 0;
virtual void detachInterrupt() = 0;
private:
};
#endif

View File

@ -133,6 +133,8 @@ void WiThrottle::parse(RingStream * stream, byte * cmdx) {
case 'P': case 'P':
if (cmd[1]=='P' && cmd[2]=='A' ) { //PPA power mode if (cmd[1]=='P' && cmd[2]=='A' ) { //PPA power mode
DCCWaveform::mainTrack.setPowerMode(cmd[3]=='1'?POWERMODE::ON:POWERMODE::OFF); DCCWaveform::mainTrack.setPowerMode(cmd[3]=='1'?POWERMODE::ON:POWERMODE::OFF);
if (MotorDriver::commonFaultPin) // commonFaultPin prevents individual track handling
DCCWaveform::progTrack.setPowerMode(cmd[3]=='1'?POWERMODE::ON:POWERMODE::OFF);
StringFormatter::send(stream,F("PPA%x\n"),DCCWaveform::mainTrack.getPowerMode()==POWERMODE::ON); StringFormatter::send(stream,F("PPA%x\n"),DCCWaveform::mainTrack.getPowerMode()==POWERMODE::ON);
lastPowerState = (DCCWaveform::mainTrack.getPowerMode()==POWERMODE::ON); //remember power state sent for comparison later lastPowerState = (DCCWaveform::mainTrack.getPowerMode()==POWERMODE::ON); //remember power state sent for comparison later
} }

View File

@ -1,3 +1,23 @@
/*
* © 2020, Chris Harlow. All rights reserved.
* © 2020, Harald Barth.
*
* This file is part of Asbelos DCC API
*
* This is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* It is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/
#ifndef ARDUINO_AVR_UNO_WIFI_REV2
#include <Arduino.h> #include <Arduino.h>
#include "WifiInboundHandler.h" #include "WifiInboundHandler.h"
#include "RingStream.h" #include "RingStream.h"
@ -228,3 +248,5 @@ void WifiInboundHandler::purgeCurrentCIPSEND() {
pendingCipsend=false; pendingCipsend=false;
clientPendingCIPSEND=-1; clientPendingCIPSEND=-1;
} }
#endif

View File

@ -15,12 +15,12 @@ class WifiInboundHandler {
static WifiInboundHandler * singleton; static WifiInboundHandler * singleton;
enum INBOUND_STATE { enum INBOUND_STATE : byte {
INBOUND_BUSY, // keep calling in loop() INBOUND_BUSY, // keep calling in loop()
INBOUND_IDLE // Nothing happening, outbound may xcall CIPSEND INBOUND_IDLE // Nothing happening, outbound may xcall CIPSEND
}; };
enum LOOP_STATE { enum LOOP_STATE : byte {
ANYTHING, // ready for +IPD, n CLOSED, n CONNECTED, busy etc... ANYTHING, // ready for +IPD, n CLOSED, n CONNECTED, busy etc...
SKIPTOEND, // skip to newline SKIPTOEND, // skip to newline

View File

@ -17,7 +17,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with CommandStation. If not, see <https://www.gnu.org/licenses/>. along with CommandStation. If not, see <https://www.gnu.org/licenses/>.
*/ */
#ifndef ARDUINO_AVR_UNO_WIFI_REV2
// This code is NOT compiled on a unoWifiRev2 processor which uses a different architecture
#include "WifiInterface.h" /* config.h included there */ #include "WifiInterface.h" /* config.h included there */
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
#include "DIAG.h" #include "DIAG.h"
@ -25,25 +26,25 @@
#include "WifiInboundHandler.h" #include "WifiInboundHandler.h"
const char PROGMEM READY_SEARCH[] = "\r\nready\r\n";
const char PROGMEM OK_SEARCH[] = "\r\nOK\r\n";
const char PROGMEM END_DETAIL_SEARCH[] = "@ 1000";
const char PROGMEM SEND_OK_SEARCH[] = "\r\nSEND OK\r\n";
const char PROGMEM IPD_SEARCH[] = "+IPD";
const unsigned long LOOP_TIMEOUT = 2000; const unsigned long LOOP_TIMEOUT = 2000;
bool WifiInterface::connected = false; bool WifiInterface::connected = false;
Stream * WifiInterface::wifiStream; Stream * WifiInterface::wifiStream;
#ifndef WIFI_CONNECT_TIMEOUT #ifndef WIFI_CONNECT_TIMEOUT
// Tested how long it takes to FAIL an unknown SSID on firmware 1.7.4. // Tested how long it takes to FAIL an unknown SSID on firmware 1.7.4.
#define WIFI_CONNECT_TIMEOUT 14000 // The ES should fail a connect in 15 seconds, we don't want to fail BEFORE that
// or ot will cause issues with the following commands.
#define WIFI_CONNECT_TIMEOUT 16000
#endif #endif
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// //
// Figure out number of serial ports depending on hardware // Figure out number of serial ports depending on hardware
// //
#if defined(ARDUINO_AVR_UNO) #if defined(ARDUINO_AVR_UNO) || defined(ARDUINO_AVR_NANO)
#define NUM_SERIAL 0 #define NUM_SERIAL 0
#endif #endif
@ -56,10 +57,11 @@ Stream * WifiInterface::wifiStream;
#endif #endif
bool WifiInterface::setup(long serial_link_speed, bool WifiInterface::setup(long serial_link_speed,
const __FlashStringHelper *wifiESSID, const FSH *wifiESSID,
const __FlashStringHelper *wifiPassword, const FSH *wifiPassword,
const __FlashStringHelper *hostname, const FSH *hostname,
const int port) { const int port,
const byte channel) {
wifiSerialState wifiUp = WIFI_NOAT; wifiSerialState wifiUp = WIFI_NOAT;
@ -70,11 +72,12 @@ bool WifiInterface::setup(long serial_link_speed,
(void) wifiPassword; (void) wifiPassword;
(void) hostname; (void) hostname;
(void) port; (void) port;
(void) channel;
#endif #endif
#if NUM_SERIAL > 0 #if NUM_SERIAL > 0
Serial1.begin(serial_link_speed); Serial1.begin(serial_link_speed);
wifiUp = setup(Serial1, wifiESSID, wifiPassword, hostname, port); wifiUp = setup(Serial1, wifiESSID, wifiPassword, hostname, port, channel);
#endif #endif
// Other serials are tried, depending on hardware. // Other serials are tried, depending on hardware.
@ -82,7 +85,7 @@ bool WifiInterface::setup(long serial_link_speed,
if (wifiUp == WIFI_NOAT) if (wifiUp == WIFI_NOAT)
{ {
Serial2.begin(serial_link_speed); Serial2.begin(serial_link_speed);
wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port); wifiUp = setup(Serial2, wifiESSID, wifiPassword, hostname, port, channel);
} }
#endif #endif
@ -90,7 +93,7 @@ bool WifiInterface::setup(long serial_link_speed,
if (wifiUp == WIFI_NOAT) if (wifiUp == WIFI_NOAT)
{ {
Serial3.begin(serial_link_speed); Serial3.begin(serial_link_speed);
wifiUp = setup(Serial3, wifiESSID, wifiPassword, hostname, port); wifiUp = setup(Serial3, wifiESSID, wifiPassword, hostname, port, channel);
} }
#endif #endif
@ -107,8 +110,8 @@ bool WifiInterface::setup(long serial_link_speed,
return connected; return connected;
} }
wifiSerialState WifiInterface::setup(Stream & setupStream, const __FlashStringHelper* SSid, const __FlashStringHelper* password, wifiSerialState WifiInterface::setup(Stream & setupStream, const FSH* SSid, const FSH* password,
const __FlashStringHelper* hostname, int port) { const FSH* hostname, int port, byte channel) {
wifiSerialState wifiState; wifiSerialState wifiState;
static uint8_t ntry = 0; static uint8_t ntry = 0;
ntry++; ntry++;
@ -117,7 +120,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const __FlashStringH
DIAG(F("\n++ Wifi Setup Try %d ++\n"), ntry); DIAG(F("\n++ Wifi Setup Try %d ++\n"), ntry);
wifiState = setup2( SSid, password, hostname, port); wifiState = setup2( SSid, password, hostname, port, channel);
if (wifiState == WIFI_NOAT) { if (wifiState == WIFI_NOAT) {
DIAG(F("\n++ Wifi Setup NO AT ++\n")); DIAG(F("\n++ Wifi Setup NO AT ++\n"));
@ -126,7 +129,7 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const __FlashStringH
if (wifiState == WIFI_CONNECTED) { if (wifiState == WIFI_CONNECTED) {
StringFormatter::send(wifiStream, F("ATE0\r\n")); // turn off the echo StringFormatter::send(wifiStream, F("ATE0\r\n")); // turn off the echo
checkForOK(200, OK_SEARCH, true); checkForOK(200, true);
} }
@ -139,146 +142,171 @@ wifiSerialState WifiInterface::setup(Stream & setupStream, const __FlashStringH
#pragma GCC diagnostic ignored "-Wunused-variable" #pragma GCC diagnostic ignored "-Wunused-variable"
#pragma GCC diagnostic ignored "-Wunused-parameter" #pragma GCC diagnostic ignored "-Wunused-parameter"
#endif #endif
wifiSerialState WifiInterface::setup2(const __FlashStringHelper* SSid, const __FlashStringHelper* password, wifiSerialState WifiInterface::setup2(const FSH* SSid, const FSH* password,
const __FlashStringHelper* hostname, int port) { const FSH* hostname, int port, byte channel) {
bool ipOK = false; bool ipOK = false;
bool oldCmd = false; bool oldCmd = false;
char macAddress[17]; // mac address extraction char macAddress[17]; // mac address extraction
// First check... Restarting the Arduino does not restart the ES. // First check... Restarting the Arduino does not restart the ES.
// There may alrerady be a connection with data in the pipeline. // There may alrerady be a connection with data in the pipeline.
// If there is, just shortcut the setup and continue to read the data as normal. // If there is, just shortcut the setup and continue to read the data as normal.
if (checkForOK(200,IPD_SEARCH, true)) { if (checkForOK(200,F("+IPD"), true)) {
DIAG(F("\nPreconfigured Wifi already running with data waiting\n")); DIAG(F("\nPreconfigured Wifi already running with data waiting\n"));
// loopstate=4; // carry on from correct place... or not as the case may be
return WIFI_CONNECTED; return WIFI_CONNECTED;
} }
StringFormatter::send(wifiStream, F("AT\r\n")); // Is something here that understands AT? StringFormatter::send(wifiStream, F("AT\r\n")); // Is something here that understands AT?
if(!checkForOK(200, OK_SEARCH, true)) if(!checkForOK(200, true))
return WIFI_NOAT; // No AT compatible WiFi module here return WIFI_NOAT; // No AT compatible WiFi module here
StringFormatter::send(wifiStream, F("ATE1\r\n")); // Turn on the echo, se we can see what's happening StringFormatter::send(wifiStream, F("ATE1\r\n")); // Turn on the echo, se we can see what's happening
checkForOK(2000, OK_SEARCH, true); // Makes this visible on the console checkForOK(2000, true); // Makes this visible on the console
// Display the AT version information // Display the AT version information
StringFormatter::send(wifiStream, F("AT+GMR\r\n")); StringFormatter::send(wifiStream, F("AT+GMR\r\n"));
checkForOK(2000, OK_SEARCH, true, false); // Makes this visible on the console checkForOK(2000, true, false); // Makes this visible on the console
#ifdef DONT_TOUCH_WIFI_CONF #ifdef DONT_TOUCH_WIFI_CONF
DIAG(F("\nDONT_TOUCH_WIFI_CONF was set: Using existing config\n")); DIAG(F("\nDONT_TOUCH_WIFI_CONF was set: Using existing config\n"));
#else #else
StringFormatter::send(wifiStream, F("AT+CWMODE=1\r\n")); // configure as "station" = WiFi client StringFormatter::send(wifiStream, F("AT+CWMODE=1\r\n")); // configure as "station" = WiFi client
checkForOK(1000, OK_SEARCH, true); // Not always OK, sometimes "no change" checkForOK(1000, true); // Not always OK, sometimes "no change"
// Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
StringFormatter::send(wifiStream, F("AT+CWJAP?\r\n"));
if (checkForOK(2000, true)) {
oldCmd=true;
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
}
// If the source code looks unconfigured, check if the
// ESP8266 is preconfigured. We check the first 13 chars
// of the SSid.
const char *yourNetwork = "Your network "; const char *yourNetwork = "Your network ";
if (strncmp_P(yourNetwork, (const char*)SSid, 13) == 0 || ((const char *)SSid)[0] == '\0') { if (strncmp_P(yourNetwork, (const char*)SSid, 13) == 0 || strncmp_P("", (const char*)SSid, 13) == 0) {
delay(8000); // give a preconfigured ES8266 a chance to connect to a router if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
// typical connect time approx 7 seconds // If the source code looks unconfigured, check if the
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // ESP8266 is preconfigured in station mode.
if (checkForOK(5000, (const char*) F("+CIFSR:STAIP"), true,false)) // We check the first 13 chars of the SSid and the password
if (!checkForOK(1000, (const char*) F("0.0.0.0"), true,false))
ipOK = true;
} else { // Should this really be "else" here /haba
if (!ipOK) {
// Older ES versions have AT+CWJAP, newer ones have AT+CWJAP_CUR and AT+CWHOSTNAME
StringFormatter::send(wifiStream, F("AT+CWJAP?\r\n"));
if (checkForOK(2000, OK_SEARCH, true)) {
oldCmd=true;
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
// give a preconfigured ES8266 a chance to connect to a router
// typical connect time approx 7 seconds
delay(8000);
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
if (!checkForOK(1000, F("0.0.0.0"), true,false))
ipOK = true;
}
} else {
// SSID was configured, so we assume station (client) mode.
if (oldCmd) {
// AT command early version supports CWJAP/CWSAP // AT command early version supports CWJAP/CWSAP
if (SSid) { StringFormatter::send(wifiStream, F("AT+CWJAP=\"%S\",\"%S\"\r\n"), SSid, password);
StringFormatter::send(wifiStream, F("AT+CWJAP=\"%S\",\"%S\"\r\n"), SSid, password); ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true);
}
DIAG(F("\n**\n"));
} else { } else {
// later version supports CWJAP_CUR // later version supports CWJAP_CUR
StringFormatter::send(wifiStream, F("AT+CWHOSTNAME=\"%S\"\r\n"), hostname); // Set Host name for Wifi Client StringFormatter::send(wifiStream, F("AT+CWHOSTNAME=\"%S\"\r\n"), hostname); // Set Host name for Wifi Client
checkForOK(2000, OK_SEARCH, true); // dont care if not supported checkForOK(2000, true); // dont care if not supported
if (SSid) { StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password);
StringFormatter::send(wifiStream, F("AT+CWJAP_CUR=\"%S\",\"%S\"\r\n"), SSid, password); ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, true);
ipOK = checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true);
}
} }
if (ipOK) { if (ipOK) {
// But we really only have the ESSID and password correct // But we really only have the ESSID and password correct
// Let's check for IP // Let's check for IP (via DHCP)
ipOK = false; ipOK = false;
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); StringFormatter::send(wifiStream, F("AT+CIFSR\r\n"));
if (checkForOK(5000, (const char*) F("+CIFSR:STAIP"), true,false)) if (checkForOK(5000, F("+CIFSR:STAIP"), true,false))
if (!checkForOK(1000, (const char*) F("0.0.0.0"), true,false)) if (!checkForOK(1000, F("0.0.0.0"), true,false))
ipOK = true; ipOK = true;
} }
}
} }
if (!ipOK) { if (!ipOK) {
// If we have not managed to get this going in station mode, go for AP mode // If we have not managed to get this going in station mode, go for AP mode
StringFormatter::send(wifiStream, F("AT+CWMODE=2\r\n")); // configure as AccessPoint. // StringFormatter::send(wifiStream, F("AT+RST\r\n"));
checkForOK(1000, OK_SEARCH, true); // Not always OK, sometimes "no change" // checkForOK(1000, true); // Not always OK, sometimes "no change"
int i=0;
do {
// configure as AccessPoint. Try really hard as this is the
// last way out to get any Wifi connectivity.
StringFormatter::send(wifiStream, F("AT+CWMODE=2\r\n"));
} while (!checkForOK(1000+i*500, true) && i++<10);
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
// Figure out MAC addr // Figure out MAC addr
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // not TOMATO
// looking fpr mac addr eg +CIFSR:APMAC,"be:dd:c2:5c:6b:b7" // looking fpr mac addr eg +CIFSR:APMAC,"be:dd:c2:5c:6b:b7"
if (checkForOK(5000, (const char*) F("+CIFSR:APMAC,\""), true,false)) { if (checkForOK(5000, F("+CIFSR:APMAC,\""), true,false)) {
// Copy 17 byte mac address // Copy 17 byte mac address
for (int i=0; i<17;i++) { for (int i=0; i<17;i++) {
while(!wifiStream->available()); while(!wifiStream->available());
macAddress[i]=wifiStream->read(); macAddress[i]=wifiStream->read();
StringFormatter::printEscape(macAddress[i]); StringFormatter::printEscape(macAddress[i]);
} }
} else {
memset(macAddress,'f',sizeof(macAddress));
} }
char macTail[]={macAddress[9],macAddress[10],macAddress[12],macAddress[13],macAddress[15],macAddress[16],'\0'}; char macTail[]={macAddress[9],macAddress[10],macAddress[12],macAddress[13],macAddress[15],macAddress[16],'\0'};
if (oldCmd) { checkForOK(1000, true, false); // suck up remainder of AT+CIFSR
while (wifiStream->available()) StringFormatter::printEscape( wifiStream->read()); /// THIS IS A DIAG IN DISGUISE
i=0;
do {
if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
// unconfigured
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"PASS_%s\",%d,4\r\n"),
oldCmd ? "" : "_CUR", macTail, macTail, channel);
} else {
// password configured by user
StringFormatter::send(wifiStream, F("AT+CWSAP%s=\"DCCEX_%s\",\"%S\",%d,4\r\n"), oldCmd ? "" : "_CUR",
macTail, password, channel);
}
} while (!checkForOK(WIFI_CONNECT_TIMEOUT, true) && i++<2); // do twice if necessary but ignore failure as AP mode may still be ok
if (i >= 2)
DIAG(F("\nWarning: Setting AP SSID and password failed\n")); // but issue warning
int i=0; if (!oldCmd) {
do {
if (strncmp_P(yourNetwork, (const char*)password, 13) == 0) {
// unconfigured
StringFormatter::send(wifiStream, F("AT+CWSAP=\"DCCEX_%s\",\"PASS_%s\",1,4\r\n"), macTail, macTail);
} else {
// password configured by user
StringFormatter::send(wifiStream, F("AT+CWSAP=\"DCCEX_%s\",\"%s\",1,4\r\n"), macTail, password);
}
} while (i++<2 && !checkForOK(WIFI_CONNECT_TIMEOUT, OK_SEARCH, true)); // do twice if necessary but ignore failure as AP mode may still be ok
} else {
StringFormatter::send(wifiStream, F("AT+CWSAP_CUR=\"DCCEX_%s\",\"PASS_%s\",1,4\r\n"), macTail, macTail);
checkForOK(20000, OK_SEARCH, true); // can ignore failure as SSid mode may still be ok
StringFormatter::send(wifiStream, F("AT+CIPRECVMODE=0\r\n"), port); // make sure transfer mode is correct StringFormatter::send(wifiStream, F("AT+CIPRECVMODE=0\r\n"), port); // make sure transfer mode is correct
checkForOK(2000, OK_SEARCH, true); checkForOK(2000, true);
} }
} }
StringFormatter::send(wifiStream, F("AT+CIPSERVER=0\r\n")); // turn off tcp server (to clean connections before CIPMUX=1) StringFormatter::send(wifiStream, F("AT+CIPSERVER=0\r\n")); // turn off tcp server (to clean connections before CIPMUX=1)
checkForOK(1000, OK_SEARCH, true); // ignore result in case it already was off checkForOK(1000, true); // ignore result in case it already was off
StringFormatter::send(wifiStream, F("AT+CIPMUX=1\r\n")); // configure for multiple connections StringFormatter::send(wifiStream, F("AT+CIPMUX=1\r\n")); // configure for multiple connections
if (!checkForOK(1000, OK_SEARCH, true)) return WIFI_DISCONNECTED; if (!checkForOK(1000, true)) return WIFI_DISCONNECTED;
StringFormatter::send(wifiStream, F("AT+CIPSERVER=1,%d\r\n"), port); // turn on server on port StringFormatter::send(wifiStream, F("AT+CIPSERVER=1,%d\r\n"), port); // turn on server on port
if (!checkForOK(1000, OK_SEARCH, true)) return WIFI_DISCONNECTED; if (!checkForOK(1000, true)) return WIFI_DISCONNECTED;
#endif //DONT_TOUCH_WIFI_CONF #endif //DONT_TOUCH_WIFI_CONF
StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // Display ip addresses to the DIAG StringFormatter::send(wifiStream, F("AT+CIFSR\r\n")); // Display ip addresses to the DIAG
if (!checkForOK(1000, OK_SEARCH, true, false)) return WIFI_DISCONNECTED; if (!checkForOK(1000, F("IP,\"") , true, false)) return WIFI_DISCONNECTED;
DIAG(F("\nPORT=%d\n"),port); // Copy the IP address
{
const byte MAX_IP_LENGTH=15;
char ipString[MAX_IP_LENGTH+1];
ipString[MAX_IP_LENGTH]='\0'; // protection against missing " character on end.
for(byte ipLen=0;ipLen<MAX_IP_LENGTH;ipLen++) {
while(!wifiStream->available());
int ipChar=wifiStream->read();
StringFormatter::printEscape(ipChar);
if (ipChar=='"') {
ipString[ipLen]='\0';
break;
}
ipString[ipLen]=ipChar;
}
LCD(4,F("%s"),ipString); // There is not enough room on some LCDs to put a title to this
}
// suck up anything after the IP.
if (!checkForOK(1000, true, false)) return WIFI_DISCONNECTED;
LCD(5,F("PORT=%d\n"),port);
return WIFI_CONNECTED; return WIFI_CONNECTED;
} }
@ -300,15 +328,19 @@ void WifiInterface::ATCommand(const byte * command) {
} }
else { else {
StringFormatter:: send(wifiStream, F("AT+%s\r\n"), command); StringFormatter:: send(wifiStream, F("AT+%s\r\n"), command);
checkForOK(10000, OK_SEARCH, true); checkForOK(10000, true);
} }
} }
bool WifiInterface::checkForOK( const unsigned int timeout, const char * waitfor, bool echo, bool escapeEcho) { bool WifiInterface::checkForOK( const unsigned int timeout, bool echo, bool escapeEcho) {
return checkForOK(timeout,F("\r\nOK\r\n"),echo,escapeEcho);
}
bool WifiInterface::checkForOK( const unsigned int timeout, const FSH * waitfor, bool echo, bool escapeEcho) {
unsigned long startTime = millis(); unsigned long startTime = millis();
char const *locator = waitfor; char *locator = (char *)waitfor;
DIAG(F("\nWifi Check: [%E]"), waitfor); DIAG(F("\nWifi Check: [%E]"), waitfor);
while ( millis() - startTime < timeout) { while ( millis() - startTime < timeout) {
while (wifiStream->available()) { while (wifiStream->available()) {
@ -317,10 +349,10 @@ bool WifiInterface::checkForOK( const unsigned int timeout, const char * waitfor
if (escapeEcho) StringFormatter::printEscape( ch); /// THIS IS A DIAG IN DISGUISE if (escapeEcho) StringFormatter::printEscape( ch); /// THIS IS A DIAG IN DISGUISE
else DIAG(F("%c"), ch); else DIAG(F("%c"), ch);
} }
if (ch != pgm_read_byte_near(locator)) locator = waitfor; if (ch != GETFLASH(locator)) locator = (char *)waitfor;
if (ch == pgm_read_byte_near(locator)) { if (ch == GETFLASH(locator)) {
locator++; locator++;
if (!pgm_read_byte_near(locator)) { if (!GETFLASH(locator)) {
DIAG(F("\nFound in %dms"), millis() - startTime); DIAG(F("\nFound in %dms"), millis() - startTime);
return true; return true;
} }
@ -337,3 +369,5 @@ void WifiInterface::loop() {
WifiInboundHandler::loop(); WifiInboundHandler::loop();
} }
} }
#endif

View File

@ -19,7 +19,7 @@
*/ */
#ifndef WifiInterface_h #ifndef WifiInterface_h
#define WifiInterface_h #define WifiInterface_h
#include "config.h" #include "FSH.h"
#include "DCCEXParser.h" #include "DCCEXParser.h"
#include <Arduino.h> #include <Arduino.h>
#include <avr/pgmspace.h> #include <avr/pgmspace.h>
@ -31,26 +31,23 @@ class WifiInterface
public: public:
static bool setup(long serial_link_speed, static bool setup(long serial_link_speed,
const __FlashStringHelper *wifiESSID, const FSH *wifiESSID,
const __FlashStringHelper *wifiPassword, const FSH *wifiPassword,
const __FlashStringHelper *hostname, const FSH *hostname,
const int port = 2560); const int port,
const byte channel);
static void loop(); static void loop();
static void ATCommand(const byte *command); static void ATCommand(const byte *command);
private: private:
static wifiSerialState setup(Stream &setupStream, const __FlashStringHelper *SSSid, const __FlashStringHelper *password, static wifiSerialState setup(Stream &setupStream, const FSH *SSSid, const FSH *password,
const __FlashStringHelper *hostname, int port); const FSH *hostname, int port, byte channel);
static Stream *wifiStream; static Stream *wifiStream;
static DCCEXParser parser; static DCCEXParser parser;
static wifiSerialState setup2(const __FlashStringHelper *SSSid, const __FlashStringHelper *password, static wifiSerialState setup2(const FSH *SSSid, const FSH *password,
const __FlashStringHelper *hostname, int port); const FSH *hostname, int port, byte channel);
static bool checkForOK(const unsigned int timeout, const char *waitfor, bool echo, bool escapeEcho = true); static bool checkForOK(const unsigned int timeout, bool echo, bool escapeEcho = true);
static bool checkForOK(const unsigned int timeout, const FSH *waitfor, bool echo, bool escapeEcho = true);
static bool connected; static bool connected;
static bool closeAfter;
static byte loopstate;
static int datalength;
static int connectionId;
static unsigned long loopTimeoutStart;
}; };
#endif #endif

View File

@ -1,10 +1,9 @@
/********************************************************************** /**********************************************************************
Config.h config.h
COPYRIGHT (c) 2013-2016 Gregg E. Berman
COPYRIGHT (c) 2020 Fred Decker COPYRIGHT (c) 2020 Fred Decker
The configuration file for DCC++ EX Command Station The configuration file for DCC-EX Command Station
**********************************************************************/ **********************************************************************/
@ -21,12 +20,12 @@ The configuration file for DCC++ EX Command Station
// POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track) // POLOLU_MOTOR_SHIELD : Pololu MC33926 Motor Driver (not recommended for prog track)
// FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection) // FUNDUMOTO_SHIELD : Fundumoto Shield, no current sensing (not recommended, no short protection)
// FIREBOX_MK1 : The Firebox MK1 // FIREBOX_MK1 : The Firebox MK1
// FIREBOX_MK1S : The Firebox MK1S // FIREBOX_MK1S : The Firebox MK1S
// IBT_2_WITH_ARDUINO : Arduino Motor Shield for PROG and IBT-2 for MAIN
// | // |
// +-----------------------v // +-----------------------v
// //
#define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD #define MOTOR_SHIELD_TYPE STANDARD_MOTOR_SHIELD
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// //
// The IP port to talk to a WIFI or Ethernet shield. // The IP port to talk to a WIFI or Ethernet shield.
@ -52,10 +51,14 @@ The configuration file for DCC++ EX Command Station
// WIFI_SSID is the network name IF you want to use your existing home network. // WIFI_SSID is the network name IF you want to use your existing home network.
// Do NOT change this if you want to use the WiFi in Access Point (AP) mode. // Do NOT change this if you want to use the WiFi in Access Point (AP) mode.
// //
// If you do NOT set the WIFI_SSID, the WiFi chip will first try // If you do NOT set the WIFI_SSID and do NOT set the WIFI_PASSWORD,
// to connect to the previously configured network and if that fails // then the WiFi chip will first try to connect to the previously
// fall back to Access Point mode. The SSID of the AP will be // configured network and if that fails fall back to Access Point mode.
// automatically set to DCCEX_*. // The SSID of the AP will be automatically set to DCCEX_*.
// If you DO set the WIFI_SSID then the WiFi chip will try to connect
// to that (home) network in station (client) mode. If a WIFI_PASSWORD
// is set (recommended), that password will be used for AP mode.
// The AP mode password must be at least 8 characters long.
// //
// Your SSID may not conain ``"'' (double quote, ASCII 0x22). // Your SSID may not conain ``"'' (double quote, ASCII 0x22).
#define WIFI_SSID "Your network name" #define WIFI_SSID "Your network name"
@ -69,12 +72,11 @@ The configuration file for DCC++ EX Command Station
// WIFI_HOSTNAME: You probably don't need to change this // WIFI_HOSTNAME: You probably don't need to change this
#define WIFI_HOSTNAME "dccex" #define WIFI_HOSTNAME "dccex"
// //
///////////////////////////////////////////////////////////////////////////////////// // WIFI_CHANNEL: If the line "#define ENABLE_WIFI true" is uncommented,
// // WiFi will be enabled (Mega only). The default channel is set to "1" whether
// Wifi connect timeout in milliseconds. Default is 14000 (14 seconds). You only need // this line exists or not. If you need to use an alternate channel (we recommend
// to set this if you have an extremely slow Wifi router. // using only 1,6, or 11) you may change it here.
// #define WIFI_CHANNEL 1
//#define WIFI_CONNECT_TIMEOUT 14000
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// //
@ -90,26 +92,6 @@ The configuration file for DCC++ EX Command Station
// //
//#define IP_ADDRESS { 192, 168, 1, 200 } //#define IP_ADDRESS { 192, 168, 1, 200 }
/////////////////////////////////////////////////////////////////////////////////////
//
// DEFINE MAC ADDRESS ARRAY FOR ETHERNET COMMUNICATIONS INTERFACE
//
// Uncomment to use with Ethernet Shields
//
// Ethernet Shields do not have have a MAC address in hardware. There may be one on
// a sticker on the Shield that you should use. Otherwise choose one of the ones below
// Be certain that no other device on your network has this same MAC address!
//
// 52:b8:8a:8e:ce:21
// e3:e9:73:e1:db:0d
// 54:2b:13:52:ac:0c
// NOTE: This is not used with ESP8266 WiFi modules.
//#define MAC_ADDRESS { 0x52, 0xB8, 0x8A, 0x8E, 0xCE, 0x21 } // MAC address of your networking card found on the sticker on your card or take one from above
//
// #define MAC_ADDRESS { 0xDE, 0xAD, 0xBE, 0xEF, 0xFE, 0xEF }
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////
// //
@ -123,8 +105,9 @@ The configuration file for DCC++ EX Command Station
// define LCD_DRIVER for I2C LCD address 0x3f,16 cols, 2 rows // define LCD_DRIVER for I2C LCD address 0x3f,16 cols, 2 rows
// #define LCD_DRIVER 0x3F,16,2 // #define LCD_DRIVER 0x3F,16,2
//OR define OLED_DRIVER width,height in pixels (address auto detected) //OR define OLED_DRIVER width,height in pixels (address auto detected)
// This will not work on a UNO due to memory constraints // 128x32 or 128x64 I2C SSD1306-based devices are supported.
// Also 132x64 I2C SH1106 devices.
// #define OLED_DRIVER 128,32 // #define OLED_DRIVER 128,32
///////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////

View File

@ -21,10 +21,13 @@
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// //
// WIFI_ON: All prereqs for running with WIFI are met // WIFI_ON: All prereqs for running with WIFI are met
// // Note: WIFI_CHANNEL may not exist in early config.h files so is added here if needed.
#if ENABLE_WIFI && (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_SAMD_ZERO)) #if ENABLE_WIFI && (defined(ARDUINO_AVR_MEGA) || defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_SAMD_ZERO))
#define WIFI_ON true #define WIFI_ON true
#ifndef WIFI_CHANNEL
#define WIFI_CHANNEL 1
#endif
#else #else
#define WIFI_ON false #define WIFI_ON false
#endif #endif

View File

@ -1,152 +0,0 @@
/*
* © 2020, Chris Harlow. All rights reserved.
*
* This file is a demonstattion of calling the DCC-EX API
*/
#include "DCCEX.h"
#ifdef ARDUINO_AVR_UNO
#include <SoftwareSerial.h>
SoftwareSerial Serial1(15,16); // YOU must get these pins correct to use Wifi on a UNO
#define WIFI_BAUD 9600
#else
#define WIFI_BAUD 115200
#endif
// this code is here to demonstrate use of the DCC API and other techniques
// myFilter is an example of an OPTIONAL command filter used to intercept < > commands from
// the usb or wifi streamm. It demonstrates how a command may be intercepted
// or even a new command created without having to break open the API library code.
// The filter is permitted to use or modify the parameter list before passing it on to
// the standard parser. By setting the opcode to 0, the standard parser will
// just ignore the command on the assumption that you have already handled it.
//
// The filter must be enabled by calling the DCC EXParser::setFilter method, see use in setup().
void myComandFilter(Print * stream, byte & opcode, byte & paramCount, int p[]) {
(void)stream; // avoid compiler warning if we don't access this parameter
switch (opcode) {
case '!': // Create a bespoke new command to clear all loco reminders <!> or specific locos e.g <! 3 4 99>
if (paramCount==0) DCC::forgetAllLocos();
else for (int i=0;i<paramCount;i++) DCC::forgetLoco(p[i]);
opcode=0; // tell parser to ignore this command as we have done it already
break;
default: // drop through and parser will use the command unaltered.
break;
}
}
// This is an OPTIONAL example of a HTTP filter...
// If you have configured wifi and an HTTP request is received on the Wifi connection
// it will normally be rejected 404 Not Found.
// If you wish to handle HTTP requests, you can create a filter and ask the WifiInterface to
// call your code for each detected http request.
void myHttpFilter(Print * stream, byte * cmd) {
(void)cmd; // Avoid compiler warning because this example doesnt use this parameter
// BEWARE - As soon as you start responding, the cmd buffer is trashed!
// You must get everything you need from it before using StringFormatter::send!
StringFormatter::send(stream,F("HTTP/1.1 200 OK\nContent-Type: text/html\nConnnection: close\n\n"));
StringFormatter::send(stream,F("<html><body>This is my HTTP filter responding.<br/></body></html>"));
}
// Callback functions are necessary if you call any API that must wait for a response from the
// programming track. The API must return immediately otherwise other loop() functions would be blocked.
// Your callback function will be invoked when the data arrives from the prog track.
// See the DCC:getLocoId example in the setup function.
void myCallback(int result) {
DIAG(F("\n getting Loco Id callback result=%d"),result);
}
// Create a serial command parser... This is OPTIONAL if you don't need to handle JMRI type commands
// from the Serial port.
DCCEXParser serialParser;
// Try monitoring the memory
#include "freeMemory.h"
int ramLowWatermark=32767; // This figure gets overwritten dynamically in loop()
void setup() {
// The main sketch has responsibilities during setup()
// Responsibility 1: Start the usb connection for diagnostics and possible JMRI input
// DIAGSERAL is normally Serial but uses SerialUSB on a SAMD processor
DIAGSERIAL.begin(115200);
while(!DIAGSERIAL);
// Responsibility 2: Start the DCC engine.
// Note: this provides DCC with two motor drivers, main and prog, which handle the motor shield(s)
// Standard supported devices have pre-configured macros but custome hardware installations require
// detailed pin mappings and may also require modified subclasses of the MotorDriver to implement specialist logic.
// STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorShields.h
// Optionally a Timer number (1..4) may be passed to DCC::begin to override the default Timer1 used for the
// waveform generation. e.g. DCC::begin(STANDARD_MOTOR_SHIELD,2); to use timer 2
DCC::begin(STANDARD_MOTOR_SHIELD);
// Responsibility 3: **Optionally** Start the WiFi interface if required.
// NOTE: On a Uno you will have to provide a SoftwareSerial
// configured for the pins connected to the Wifi card
// and a 9600 baud rate.
// setup(serial, F(router name) or NULL, F(router password), F(hostname), F(AcessPoint name) or NULL , port)
// (port 3532 is 0xDCC decimal.)
Serial1.begin(WIFI_BAUD);
WifiInterface::setup(Serial1, F("BTHub5-M6PT"), F("49de8d4862"),F("DCCEX"),3532);
// Optionally tell the Wifi parser to use my http filter.
// This will intercept http commands from Wifi.
WifiInterface::setHTTPCallback(myHttpFilter);
// This is just for demonstration purposes
DIAG(F("\n===== DCCEX demonstrating DCC::getLocoId() call ==========\n"));
DCC::getLocoId(myCallback); // myCallback will be called with the result
DIAG(F("\n===== DCC::getLocoId has returned, but the callback wont be executed until we are in loop() ======\n"));
// Optionally tell the command parser to use my example filter.
// This will intercept JMRI commands from both USB and Wifi
DCCEXParser::setFilter(myComandFilter);
DIAG(F("\nReady for JMRI commands\n"));
}
void loop() {
// The main sketch has responsibilities during loop()
// Responsibility 1: Handle DCC background processes
// (loco reminders and power checks)
DCC::loop();
// Responsibility 2: handle any incoming commands on USB connection
serialParser.loop(DIAGSERIAL);
// Responsibility 3: Optionally handle any incoming WiFi traffic
WifiInterface::loop();
// Your additional loop code
// Optionally report any decrease in memory (will automatically trigger on first call)
int freeNow=freeMemory();
if (freeNow<ramLowWatermark) {
ramLowWatermark=freeNow;
DIAG(F("\nFree RAM=%d\n"),ramLowWatermark);
}
}

View File

@ -1,29 +0,0 @@
/*
* © 2020, Chris Harlow. All rights reserved.
*
* This is a basic, no frills DCC-EX example of a DCC++ compatible setup.
* There are more advanced examples in the examples folder i
*/
#include "DCCEX.h"
// Create parser for <> commands coming from keyboard or JMRI on thr USB connection.
DCCEXParser serialParser;
void setup() {
// Responsibility 1: Start the usb connection for diagnostics and possible JMRI input
Serial.begin(115200);
// Responsibility 2: Start the DCC engine with information about your Motor Shield.
// STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorDriverss.h
DCC::begin(STANDARD_MOTOR_SHIELD);
}
void loop() {
// Responsibility 1: Handle DCC background processes (loco reminders and power checks)
DCC::loop();
// Responsibility 2: handle any incoming commands on USB connection
serialParser.loop(Serial);
}

View File

@ -1,73 +0,0 @@
/*
* © 2020, Chris Harlow. All rights reserved.
*
* This file is a demonstattion of setting up a DCC-EX
* Command station to support direct connection of WiThrottle devices
* such as "Engine Driver". If you contriol your layout through JMRI
* then DON'T connect throttles to this wifi, connect them to JMRI.
*
* This is just 3 statements longer than the basic setup.
*
* THIS SETUP DOES NOT APPLY TO ARDUINO UNO WITH ONLY A SINGLE SERIAL PORT.
* REFER TO SEPARATE EXAMPLE.
*/
#include "DCCEX.h"
// Create a serial command parser... Enables certain diagnostics and commands
// to be issued from the USB serial console
// This is NOT intended for JMRI....
DCCEXParser serialParser;
void setup() {
// The main sketch has responsibilities during setup()
// Responsibility 1: Start the usb connection for diagnostics
// This is normally Serial but uses SerialUSB on a SAMD processor
Serial.begin(115200);
// Responsibility 3: Start the DCC engine.
// Note: this provides DCC with two motor drivers, main and prog, which handle the motor shield(s)
// Standard supported devices have pre-configured macros but custome hardware installations require
// detailed pin mappings and may also require modified subclasses of the MotorDriver to implement specialist logic.
// STANDARD_MOTOR_SHIELD, POLOLU_MOTOR_SHIELD, FIREBOX_MK1, FIREBOX_MK1S are pre defined in MotorShields.h
// Optionally a Timer number (1..4) may be passed to DCC::begin to override the default Timer1 used for the
// waveform generation. e.g. DCC::begin(STANDARD_MOTOR_SHIELD,2); to use timer 2
DCC::begin(STANDARD_MOTOR_SHIELD);
// Start the WiFi interface.
// NOTE: References to Serial1 are for the serial port used to connect
// your wifi chip/shield.
Serial1.begin(115200); // BAUD rate of your Wifi chip/shield
WifiInterface::setup(Serial1,
F("BTHub5-M6PT"), // Router name
F("49de8d4862"), // Router password
F("DCCEX"), // Hostname (ignored by some wifi chip firmware)
3532); // port (3532 is 0xDCC)
}
void loop() {
// The main sketch has responsibilities during loop()
// Responsibility 1: Handle DCC background processes
// (loco reminders and power checks)
DCC::loop();
// Responsibility 2: handle any incoming commands on USB connection
serialParser.loop(Serial);
// Responsibility 3: Optionally handle any incoming WiFi traffic
WifiInterface::loop();
}

View File

@ -10,5 +10,7 @@ ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -x -C %ELF% | find ".data" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt avr-objdump -x -C %ELF% | find ".data" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt
ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -x -C %ELF% | find ".bss" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt avr-objdump -x -C %ELF% | find ".bss" | sort /+25 /R >>%TMP%\OBJDUMP_%a%.txt
notepad %TMP%\OBJDUMP_%a%.txt ECHO ++++++++++++++++++++++++++++++++++ >>%TMP%\OBJDUMP_%a%.txt
avr-objdump -D -S %ELF% >>%TMP%\OBJDUMP_%a%.txt
%TMP%\OBJDUMP_%a%.txt
EXIT EXIT

View File

@ -36,10 +36,6 @@ lib_deps =
DIO2 DIO2
arduino-libraries/Ethernet arduino-libraries/Ethernet
SPI SPI
marcoschwartz/LiquidCrystal_I2C
Adafruit/Adafruit_BusIO
Adafruit/Adafruit_SSD1306
Adafruit/Adafruit-GFX-Library
monitor_speed = 115200 monitor_speed = 115200
monitor_flags = --echo monitor_flags = --echo
@ -52,7 +48,6 @@ lib_deps =
DIO2 DIO2
arduino-libraries/Ethernet arduino-libraries/Ethernet
SPI SPI
marcoschwartz/LiquidCrystal_I2C
monitor_speed = 115200 monitor_speed = 115200
monitor_flags = --echo monitor_flags = --echo
@ -65,9 +60,9 @@ lib_deps =
DIO2 DIO2
arduino-libraries/Ethernet arduino-libraries/Ethernet
SPI SPI
marcoschwartz/LiquidCrystal_I2C
monitor_speed = 115200 monitor_speed = 115200
monitor_flags = --echo monitor_flags = --echo
build_flags = "-DF_CPU=16000000L -DARDUINO=10813 -DARDUINO_AVR_UNO_WIFI_DEV_ED -DARDUINO_ARCH_AVR -DESP_CH_UART -DESP_CH_UART_BR=19200"g
[env:uno] [env:uno]
platform = atmelavr platform = atmelavr
@ -78,6 +73,5 @@ lib_deps =
DIO2 DIO2
arduino-libraries/Ethernet arduino-libraries/Ethernet
SPI SPI
marcoschwartz/LiquidCrystal_I2C
monitor_speed = 115200 monitor_speed = 115200
monitor_flags = --echo monitor_flags = --echo

View File

@ -3,8 +3,9 @@
#include "StringFormatter.h" #include "StringFormatter.h"
// const char VERSION[] PROGMEM ="0.2.0"; #define VERSION "3.0.4"
#define VERSION "3.0.3" // 3.0.4 Includes:
// Wifi startup bugfixes
// 3.0.3 Includes: // 3.0.3 Includes:
// <W addr> command to write loco address and clear consist // <W addr> command to write loco address and clear consist
// <R> command will allow for consist address // <R> command will allow for consist address