diff --git a/DCC.h b/DCC.h
index a7646a8..1e07bfe 100644
--- a/DCC.h
+++ b/DCC.h
@@ -164,6 +164,8 @@ private:
#define ARDUINO_TYPE "MEGA"
#elif defined(ARDUINO_ARCH_MEGAAVR)
#define ARDUINO_TYPE "MEGAAVR"
+#elif defined(ARDUINO_ARCH_RP2040)
+#define ARDUINO_TYPE "RP2040"
#else
#error CANNOT COMPILE - DCC++ EX ONLY WORKS WITH AN ARDUINO UNO, NANO 328, OR ARDUINO MEGA 1280/2560
#endif
diff --git a/DCCTimer.cpp b/DCCTimer.cpp
index 46cd2ea..9a5ecf9 100644
--- a/DCCTimer.cpp
+++ b/DCCTimer.cpp
@@ -43,12 +43,13 @@
*/
#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
+#if defined(ARDUINO_ARCH_MEGAAVR)
// Arduino unoWifi Rev2 and nanoEvery architectire
void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
@@ -83,7 +84,24 @@ INTERRUPT_CALLBACK interruptHandler=0;
memcpy(mac,(void *) &SIGROW.SERNUM0,6); // serial number
}
-#else
+#elif defined(ARDUINO_ARCH_RP2040)
+ // RP2040 aka Raspberry PI Pico
+ void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
+ interruptHandler=callback;
+ }
+
+ 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
diff --git a/DCCTimer.h b/DCCTimer.h
index dfe9ef2..e20a979 100644
--- a/DCCTimer.h
+++ b/DCCTimer.h
@@ -1,6 +1,9 @@
#ifndef DCCTimer_h
#define DCCTimer_h
#include "Arduino.h"
+#if defined(ARDUINO_ARCH_RP2040)
+#include "pico/stdlib.h"
+#endif
typedef void (*INTERRUPT_CALLBACK)();
diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp
deleted file mode 100644
index 439717e..0000000
--- a/DCCWaveform.cpp
+++ /dev/null
@@ -1,313 +0,0 @@
-/*
- * © 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 .
- */
- #pragma GCC optimize ("-O3")
-#include
-
-#include "DCCWaveform.h"
-#include "DCCTimer.h"
-#include "DIAG.h"
-
-
-DCCWaveform DCCWaveform::mainTrack(PREAMBLE_BITS_MAIN, true);
-DCCWaveform DCCWaveform::progTrack(PREAMBLE_BITS_PROG, false);
-
-
-bool DCCWaveform::progTrackSyncMain=false;
-bool DCCWaveform::progTrackBoosted=false;
-int DCCWaveform::progTripValue=0;
-
-void DCCWaveform::begin(MotorDriver * mainDriver, MotorDriver * progDriver) {
- mainTrack.motorDriver=mainDriver;
- progTrack.motorDriver=progDriver;
- progTripValue = progDriver->mA2raw(TRIP_CURRENT_PROG); // need only calculate once hence static
- mainTrack.setPowerMode(POWERMODE::OFF);
- progTrack.setPowerMode(POWERMODE::OFF);
- MotorDriver::usePWM= mainDriver->isPWMCapable() && progDriver->isPWMCapable();
- if (MotorDriver::usePWM) DIAG(F("\nWaveform using PWM pins for accuracy."));
- else DIAG(F("\nWaveform accuracy limited by signal pin configuration."));
- DCCTimer::begin(DCCWaveform::interruptHandler);
-}
-
-void DCCWaveform::loop() {
- mainTrack.checkPowerOverload();
- progTrack.checkPowerOverload();
-}
-
-void DCCWaveform::interruptHandler() {
- // call the timer edge sensitive actions for progtrack and maintrack
- // member functions would be cleaner but have more overhead
- 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();
-
-}
-
-
-// An instance of this class handles the DCC transmissions for one track. (main or prog)
-// Interrupts are marshalled via the statics.
-// A track has a current transmit buffer, and a pending buffer.
-// When the current buffer is exhausted, either the pending buffer (if there is one waiting) or an idle buffer.
-
-
-// This bitmask has 9 entries as each byte is trasmitted as a zero + 8 bits.
-const byte bitMask[] = {0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01};
-
-
-DCCWaveform::DCCWaveform( byte preambleBits, bool isMain) {
- isMainTrack = isMain;
- packetPending = false;
- memcpy(transmitPacket, idlePacket, sizeof(idlePacket));
- state = WAVE_START;
- // The +1 below is to allow the preamble generator to create the stop bit
- // for the previous packet.
- requiredPreambles = preambleBits+1;
- bytes_sent = 0;
- bits_sent = 0;
- sampleDelay = 0;
- lastSampleTaken = millis();
- ackPending=false;
-}
-
-POWERMODE DCCWaveform::getPowerMode() {
- return powerMode;
-}
-
-void DCCWaveform::setPowerMode(POWERMODE mode) {
- powerMode = mode;
- bool ison = (mode == POWERMODE::ON);
- motorDriver->setPower( ison);
-}
-
-
-void DCCWaveform::checkPowerOverload() {
- if (millis() - lastSampleTaken < sampleDelay) return;
- lastSampleTaken = millis();
- int tripValue= motorDriver->getRawCurrentTripValue();
- if (!isMainTrack && !ackPending && !progTrackSyncMain && !progTrackBoosted)
- tripValue=progTripValue;
-
- switch (powerMode) {
- case POWERMODE::OFF:
- sampleDelay = POWER_SAMPLE_OFF_WAIT;
- break;
- case POWERMODE::ON:
- // Check current
- lastCurrent=motorDriver->getCurrentRaw();
- if (lastCurrent < 0) {
- // We have a fault pin condition to take care of
- DIAG(F("\n*** %S FAULT PIN ACTIVE TOGGLE POWER ON THIS OR BOTH TRACKS ***\n"), isMainTrack ? F("MAIN") : F("PROG"));
- lastCurrent = -lastCurrent;
- }
- if (lastCurrent <= tripValue) {
- sampleDelay = POWER_SAMPLE_ON_WAIT;
- if(power_good_counter<100)
- power_good_counter++;
- else
- if (power_sample_overload_wait>POWER_SAMPLE_OVERLOAD_WAIT) power_sample_overload_wait=POWER_SAMPLE_OVERLOAD_WAIT;
- } else {
- setPowerMode(POWERMODE::OVERLOAD);
- unsigned int mA=motorDriver->raw2mA(lastCurrent);
- unsigned int maxmA=motorDriver->raw2mA(tripValue);
- power_good_counter=0;
- 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)
- power_sample_overload_wait = 10000;
- else
- power_sample_overload_wait *= 2;
- }
- break;
- case POWERMODE::OVERLOAD:
- // Try setting it back on after the OVERLOAD_WAIT
- setPowerMode(POWERMODE::ON);
- sampleDelay = POWER_SAMPLE_ON_WAIT;
- // Debug code....
- DIAG(F("\n*** %S TRACK POWER RESET delay=%d ***\n"), isMainTrack ? F("MAIN") : F("PROG"), sampleDelay);
- break;
- default:
- 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,
- /* WAVE_HIGH_0 -> */ HIGH,
- /* WAVE_MID_0 -> */ LOW,
- /* WAVE_LOW_0 -> */ LOW,
- /* WAVE_PENDING (should not happen) -> */ LOW};
-
-void DCCWaveform::interrupt2() {
- // 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 ) {
- state=WAVE_MID_1; // switch state to trigger LOW on next interrupt
- remainingPreambles--;
- 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
- state=(transmitPacket[bytes_sent] & bitMask[bits_sent])? WAVE_MID_1 : WAVE_HIGH_0;
- bits_sent++;
-
- // If this is the last bit of a byte, prepare for the next byte
-
- if (bits_sent == 9) { // zero followed by 8 bits of a byte
- //end of Byte
- bits_sent = 0;
- bytes_sent++;
- // if this is the last byte, prepere for next packet
- if (bytes_sent >= transmitLength) {
- // end of transmission buffer... repeat or switch to next message
- bytes_sent = 0;
- remainingPreambles = requiredPreambles;
-
- if (transmitRepeats > 0) {
- transmitRepeats--;
- }
- else if (packetPending) {
- // Copy pending packet to transmit packet
- // 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;
- transmitRepeats = pendingRepeats;
- packetPending = false;
- sentResetsSincePacket=0;
- }
- else {
- // Fortunately reset and idle packets are the same length
- memcpy( transmitPacket, isMainTrack ? idlePacket : resetPacket, sizeof(idlePacket));
- transmitLength = sizeof(idlePacket);
- transmitRepeats = 0;
- if (sentResetsSincePacket<250) sentResetsSincePacket++;
- }
- }
- }
-}
-
-
-
-// Wait until there is no packet pending, then make this pending
-void DCCWaveform::schedulePacket(const byte buffer[], byte byteCount, byte repeats) {
- if (byteCount >= MAX_PACKET_SIZE) return; // allow for chksum
- while (packetPending);
-
- byte checksum = 0;
- for (byte b = 0; b < byteCount; b++) {
- checksum ^= buffer[b];
- pendingPacket[b] = buffer[b];
- }
- pendingPacket[byteCount] = checksum;
- pendingLength = byteCount + 1;
- pendingRepeats = repeats;
- packetPending = true;
- sentResetsSincePacket=0;
-}
-
-// Operations applicable to PROG track ONLY.
-// (yes I know I could have subclassed the main track but...)
-
-void DCCWaveform::setAckBaseline() {
- if (isMainTrack) return;
- int baseline=motorDriver->getCurrentRaw();
- ackThreshold= baseline + motorDriver->mA2raw(ackLimitmA);
- if (Diag::ACK) DIAG(F("\nACK baseline=%d/%dmA Threshold=%d/%dmA Duration: %dus <= pulse <= %dus"),
- baseline,motorDriver->raw2mA(baseline),
- ackThreshold,motorDriver->raw2mA(ackThreshold),
- minAckPulseDuration, maxAckPulseDuration);
-}
-
-void DCCWaveform::setAckPending() {
- if (isMainTrack) return;
- ackMaxCurrent=0;
- ackPulseStart=0;
- ackPulseDuration=0;
- ackDetected=false;
- ackCheckStart=millis();
- ackPending=true; // interrupt routines will now take note
-}
-
-byte DCCWaveform::getAck() {
- if (ackPending) return (2); // still waiting
- if (Diag::ACK) DIAG(F("\n%S after %dmS max=%d/%dmA pulse=%duS"),ackDetected?F("ACK"):F("NO-ACK"), ackCheckDuration,
- ackMaxCurrent,motorDriver->raw2mA(ackMaxCurrent), ackPulseDuration);
- if (ackDetected) return (1); // Yes we had an ack
- return(0); // pending set off but not detected means no ACK.
-}
-
-void DCCWaveform::checkAck() {
- // This function operates in interrupt() time so must be fast and can't DIAG
- if (sentResetsSincePacket > 6) { //ACK timeout
- ackCheckDuration=millis()-ackCheckStart;
- ackPending = false;
- return;
- }
-
- int current=motorDriver->getCurrentRaw();
- if (current > ackMaxCurrent) ackMaxCurrent=current;
- // An ACK is a pulse lasting between minAckPulseDuration and maxAckPulseDuration uSecs (refer @haba)
-
- if (current>ackThreshold) {
- if (ackPulseStart==0) ackPulseStart=micros(); // leading edge of pulse detected
- return;
- }
-
- // not in pulse
- if (ackPulseStart==0) return; // keep waiting for leading edge
-
- // detected trailing edge of pulse
- ackPulseDuration=micros()-ackPulseStart;
-
- if (ackPulseDuration>=minAckPulseDuration && ackPulseDuration<=maxAckPulseDuration) {
- ackCheckDuration=millis()-ackCheckStart;
- ackDetected=true;
- ackPending=false;
- transmitRepeats=0; // shortcut remaining repeat packets
- return; // we have a genuine ACK result
- }
- ackPulseStart=0; // We have detected a too-short or too-long pulse so ignore and wait for next leading edge
-}
diff --git a/EEStore.cpp b/EEStore.cpp
index 14ed925..999c652 100644
--- a/EEStore.cpp
+++ b/EEStore.cpp
@@ -24,7 +24,7 @@
#include "Outputs.h"
#include "DIAG.h"
-#if defined(ARDUINO_ARCH_SAMD)
+#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_RP2040)
ExternalEEPROM EEPROM;
#endif
diff --git a/EEStore.h b/EEStore.h
index b1d6d31..83b1afc 100644
--- a/EEStore.h
+++ b/EEStore.h
@@ -3,7 +3,7 @@
#include
-#if defined(ARDUINO_ARCH_SAMD)
+#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_RP2040)
#include
extern ExternalEEPROM EEPROM;
#else
diff --git a/platformio.ini b/platformio.ini
index be539ff..30141f4 100644
--- a/platformio.ini
+++ b/platformio.ini
@@ -101,3 +101,16 @@ lib_deps =
PaulStoffregen/TimerOne
monitor_speed = 115200
monitor_flags = --echo
+
+[env:pico]
+platform = https://github.com/maxgerhardt/platform-raspberrypi.git
+board = pico
+framework = arduino
+board_build.core = earlephilhower
+lib_deps =
+ ${env.lib_deps}
+ DIO2
+ arduino-libraries/Ethernet
+ SPI
+ marcoschwartz/LiquidCrystal_I2C
+ SparkFun External EEPROM Arduino Library
\ No newline at end of file