diff --git a/.gitignore b/.gitignore
index 6237359..9f44e98 100644
--- a/.gitignore
+++ b/.gitignore
@@ -13,3 +13,4 @@ myFilter.cpp
my*.h
!my*.example.h
compile_commands.json
+*.yaml
diff --git a/DCCTimerRP2040.cpp b/DCCTimerRP2040.cpp
new file mode 100644
index 0000000..ae03836
--- /dev/null
+++ b/DCCTimerRP2040.cpp
@@ -0,0 +1,165 @@
+/*
+ * © 2020-2022 Harald Barth
+ *
+ * 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 .
+ */
+
+////////////////////////////////////////////////////////////////////////
+#ifdef ARDUINO_ARCH_RP2040
+
+#include "pico/stdlib.h"
+
+#include
+#include
+#include
+#include
+#include
+#include "hardware/timer.h"
+#include "hardware/irq.h"
+
+#if defined(ADC_INPUT_MAX_VALUE)
+#undef ADC_INPUT_MAX_VALUE
+#endif
+#define ADC_INPUT_MAX_VALUE 4095 // 12 bit ADC
+#define NUM_ADC_INPUTS 4
+
+#include "DCCTimer.h"
+INTERRUPT_CALLBACK interruptHandler=0;
+
+#define ALARM_NUM 0
+#define ALARM_IRQ TIMER_IRQ_0
+
+static uint32_t dcc_signal_time = 0;
+
+static void alarm_irq(void) {
+ // Clear the alarm irq
+ hw_clear_bits(&timer_hw->intr, 1u << ALARM_NUM);
+ // Reload timer
+ uint64_t target = timer_hw->timerawl + dcc_signal_time;
+ timer_hw->alarm[ALARM_NUM] = (uint32_t) target;
+
+ if (interruptHandler)
+ interruptHandler();
+}
+
+void DCCTimer::begin(INTERRUPT_CALLBACK callback) {
+ interruptHandler = callback;
+ dcc_signal_time = DCC_SIGNAL_TIME;
+ // Enable the interrupt for our alarm (the timer outputs 4 alarm irqs)
+ hw_set_bits(&timer_hw->inte, 1u << ALARM_NUM);
+ // Set irq handler for alarm irq
+ irq_set_exclusive_handler(ALARM_IRQ, alarm_irq);
+ // Enable the alarm irq
+ irq_set_enabled(ALARM_IRQ, true);
+ // Enable interrupt in block and at processor
+
+ // Alarm is only 32 bits so if trying to delay more
+ // than that need to be careful and keep track of the upper
+ // bits
+ uint64_t target = timer_hw->timerawl + dcc_signal_time;
+
+ // Write the lower 32 bits of the target time to the alarm which
+ // will arm it
+ timer_hw->alarm[ALARM_NUM] = (uint32_t) target;
+}
+
+// All pins are PWM capable
+bool DCCTimer::isPWMPin(byte pin) {
+ return false;
+}
+
+void DCCTimer::setPWM(byte pin, bool high) {
+ (void) pin;
+ (void) high;
+}
+
+void DCCTimer::clearPWM() {
+}
+
+// Fake this as it should not be used
+void DCCTimer::getSimulatedMacAddress(byte mac[6]) {
+ mac[0] = 0xFE;
+ mac[1] = 0xBE;
+ mac[2] = 0xEF;
+ mac[3] = 0xC0;
+ mac[4] = 0xFF;
+ mac[5] = 0xEE;
+}
+
+volatile int DCCTimer::minimum_free_memory=__INT_MAX__;
+
+// Return low memory value...
+int DCCTimer::getMinimumFreeMemory() {
+ noInterrupts(); // Disable interrupts to get volatile value
+ int retval = minimum_free_memory;
+ interrupts();
+ return retval;
+}
+
+int DCCTimer::freeMemory() {
+ return rp2040.getFreeHeap();
+}
+
+void DCCTimer::reset() {
+ rp2040.reboot();
+}
+
+void DCCTimer::DCCEXanalogWriteFrequency(uint8_t pin, uint32_t frequency) {
+ (void) pin; /* Can't set different frequencies on different pins */
+ analogWriteFreq(frequency);
+}
+
+void DCCTimer::DCCEXanalogWrite(uint8_t pin, int value) {
+ analogWrite(pin, value);
+}
+
+int ADCee::init(uint8_t pin) {
+ uint8_t id = pin - A0;
+ int value = 0;
+
+ if (id > NUM_ADC_INPUTS)
+ return -1023;
+
+ adc_gpio_init(pin);
+ adc_select_input(pin);
+
+ return(adc_read());
+}
+
+int16_t ADCee::ADCmax() {
+ return ADC_INPUT_MAX_VALUE;
+}
+
+/*
+ * Read function ADCee::read(pin) to get value instead of analogRead(pin)
+ */
+int ADCee::read(uint8_t pin, bool fromISR) {
+ adc_select_input(pin);
+
+ return(adc_read());
+}
+
+/*
+ * Scan function that is called from interrupt
+ */
+void ADCee::scan() {
+}
+
+void ADCee::begin() {
+ adc_init();
+}
+
+#endif // RP2040
diff --git a/DCCWaveform.cpp b/DCCWaveform.cpp
index 4a99997..53cab96 100644
--- a/DCCWaveform.cpp
+++ b/DCCWaveform.cpp
@@ -62,7 +62,7 @@ const bool signalTransform[]={
/* WAVE_PENDING (should not happen) -> */ LOW};
void DCCWaveform::begin() {
- DCCTimer::begin(DCCWaveform::interruptHandler);
+ DCCTimer::begin(DCCWaveform::interruptHandler);
}
void DCCWaveform::loop() {
diff --git a/MotorDriver.cpp b/MotorDriver.cpp
index d5dca13..0ff088f 100644
--- a/MotorDriver.cpp
+++ b/MotorDriver.cpp
@@ -91,7 +91,7 @@ MotorDriver::MotorDriver(int16_t power_pin, byte signal_pin, byte signal_pin2, i
}
}
else dualSignal=false;
-
+
if (brake_pin!=UNUSED_PIN){
invertBrake=brake_pin < 0;
if (invertBrake)
diff --git a/MotorDriver.h b/MotorDriver.h
index 21bceb6..84d2e03 100644
--- a/MotorDriver.h
+++ b/MotorDriver.h
@@ -61,6 +61,10 @@ enum TRACK_MODE : byte {TRACK_MODE_NONE = 1, TRACK_MODE_MAIN = 2, TRACK_MODE_PRO
#define PORTC GPIOC->ODR
#define HAVE_PORTC(X) X
#endif
+#if defined(ARDUINO_ARCH_RP2040)
+#define HAVE_PORTA(X) X
+#define PORTA (sio_hw->gpio_out)
+#endif
// if macros not defined as pass-through we define
// them here as someting that is valid as a
@@ -92,7 +96,7 @@ public:
byte invpin = UNUSED_PIN;
};
-#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
+#if defined(__IMXRT1062__) || defined(ARDUINO_ARCH_ESP8266) || defined(ARDUINO_ARCH_ESP32) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32) || defined(ARDUINO_ARCH_RP2040)
typedef uint32_t portreg_t;
#else
typedef uint8_t portreg_t;
diff --git a/MotorDrivers.h b/MotorDrivers.h
index 907c11b..2282238 100644
--- a/MotorDrivers.h
+++ b/MotorDrivers.h
@@ -59,7 +59,21 @@
// Arduino STANDARD Motor Shield, used on different architectures:
-#if defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
+#if defined(ARDUINO_ARCH_RP2040)
+// Standard Motor Shield definition for RP2040
+// This setup is for the iLabs Challenger NB RP2040 WiFi board. Other boards likely need
+// a separate setup.
+#define STANDARD_MOTOR_SHIELD "STANDARD_MOTOR_SHIELD", \
+ new MotorDriver(D17, D16, UNUSED_PIN, D15, A0, 0.488, 1500, UNUSED_PIN), \
+ new MotorDriver(D14, D13, UNUSED_PIN, D12, A1, 0.488, 1500, UNUSED_PIN)
+#define RP2040_STANDARD_MOTOR_SHIELD STANDARD_MOTOR_SHIELD
+
+// EX 8874 based shield connected to a 3V3 system with 12-bit (4096) ADC
+#define EX8874_SHIELD "EX8874", \
+ new MotorDriver(D17, D16, UNUSED_PIN, D15, A0, 1.27, 5000, A4), \
+ new MotorDriver(D14, D13, UNUSED_PIN, D12, A1, 1.27, 5000, A5)
+
+#elif defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_STM32)
// Standard Motor Shield definition for 3v3 processors (other than the ESP32)
// Setup for SAMD21 Sparkfun DEV board MUST use Arduino Motor Shield R3 (MUST be R3
// for 3v3 compatibility!!) senseFactor for 3.3v systems is 1.95 as calculated when using
diff --git a/SSD1306Ascii.cpp b/SSD1306Ascii.cpp
index ea0c76b..3ada0c3 100644
--- a/SSD1306Ascii.cpp
+++ b/SSD1306Ascii.cpp
@@ -159,7 +159,14 @@ SSD1306AsciiWire::SSD1306AsciiWire(I2CAddress address, int width, int height) {
bool SSD1306AsciiWire::begin() {
I2CManager.begin();
- I2CManager.setClock(400000L); // Set max supported I2C speede
+ I2CManager.setClock(400000L); // Set max supported I2C speed
+
+#if defined(OLED_HAS_RESET_PIN)
+ pinMode(OLED_HAS_RESET_PIN, OUTPUT);
+ digitalWrite(OLED_HAS_RESET_PIN, LOW);
+ delay(1);
+ digitalWrite(OLED_HAS_RESET_PIN, HIGH);
+#endif
if (m_i2cAddr == 0) {
// Probe for I2C device on 0x3c and 0x3d.
diff --git a/WifiInterface.cpp b/WifiInterface.cpp
index 8b2251a..cf95cd8 100644
--- a/WifiInterface.cpp
+++ b/WifiInterface.cpp
@@ -76,6 +76,11 @@ Stream * WifiInterface::wifiStream;
#endif
#endif
+#if defined(ARDUINO_ARCH_RP2040)
+#define NUM_SERIAL 2
+#define SERIAL1 Serial2
+#endif
+
#ifndef NUM_SERIAL
#define NUM_SERIAL 1
#define SERIAL1 Serial1
diff --git a/config.example.h b/config.example.h
index 0f136f9..11d7fe3 100644
--- a/config.example.h
+++ b/config.example.h
@@ -160,6 +160,9 @@ The configuration file for DCC-EX Command Station
// 128x32 or 128x64 I2C SSD1306-based devices are supported.
// Use 132,64 for a SH1106-based I2C device with a 128x64 display.
// #define OLED_DRIVER 0x3c,128,32
+// Some OLED displays have an external reset pin that needs to be managed. Set the following
+// macro to point to that pin.
+// #define OLED_HAS_RESET_PIN 5
// Define scroll mode as 0, 1 or 2
// * #define SCROLLMODE 0 is scroll continuous (fill screen if poss),
diff --git a/defines.h b/defines.h
index f3822ca..7a33bbb 100644
--- a/defines.h
+++ b/defines.h
@@ -147,12 +147,8 @@
#ifndef I2C_USE_WIRE
#define I2C_USE_WIRE
#endif
-
-/* TODO when ready
#elif defined(ARDUINO_ARCH_RP2040)
#define ARDUINO_TYPE "RP2040"
-*/
-
#else
#define CPU_TYPE_ERROR
#endif
@@ -212,6 +208,7 @@
// Currently only devices which can communicate at 115200 are supported.
//
#define WIFI_SERIAL_LINK_SPEED 115200
+#define WIFI_SERIAL_PORT Serial2
#if __has_include ( "myAutomation.h")
#if defined(HAS_ENOUGH_MEMORY) || defined(DISABLE_EEPROM) || defined(DISABLE_PROG)