Browse Source

✨ RP2040 HAL with BTT SKR Pico (#24042)

Scott Lahteine 4 months ago
parent
commit
d876b5ee3c

+ 3 - 0
.github/workflows/ci-build-tests.yml

@@ -41,6 +41,9 @@ jobs:
       matrix:
         test-platform:
 
+        # RP2040
+        - SKR_Pico
+
         # Native
         - linux_native
         - simulator_linux_release

+ 1 - 1
Marlin/Makefile

@@ -1026,7 +1026,7 @@ extcoff: $(TARGET).elf
 	$(NM) -n $< > $@
 
 # Link: create ELF output file from library.
-
+LDFLAGS+= -Wl,-V
 $(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h
 	$(Pecho) "  CXX   $@"
 	$P $(CXX) $(LD_PREFIX) $(ALL_CXXFLAGS) -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX)

+ 188 - 0
Marlin/src/HAL/RP2040/HAL.cpp

@@ -0,0 +1,188 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "HAL.h"
+//#include "usb_serial.h"
+
+#include "../../inc/MarlinConfig.h"
+#include "../shared/Delay.h"
+
+extern "C" {
+  #include "pico/bootrom.h"
+  #include "hardware/watchdog.h"
+}
+
+#if HAS_SD_HOST_DRIVE
+  #include "msc_sd.h"
+  #include "usbd_cdc_if.h"
+#endif
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+volatile uint16_t adc_result;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
+
+// HAL initialization task
+void MarlinHAL::init() {
+  // Ensure F_CPU is a constant expression.
+  // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
+  // So better safe than sorry here.
+  constexpr int cpuFreq = F_CPU;
+  UNUSED(cpuFreq);
+
+  #undef SDSS
+  #define SDSS 2
+  #define PIN_EXISTS_(P1,P2) (defined(P1##P2) && P1##P2 >= 0)
+  #if HAS_MEDIA && DISABLED(SDIO_SUPPORT) && PIN_EXISTS_(SDSS,)
+    OUT_WRITE(SDSS, HIGH); // Try to set SDSS inactive before any other SPI users start up
+  #endif
+
+  #if PIN_EXISTS(LED)
+    OUT_WRITE(LED_PIN, LOW);
+  #endif
+
+  #if ENABLED(SRAM_EEPROM_EMULATION)
+    // __HAL_RCC_PWR_CLK_ENABLE();
+    // HAL_PWR_EnableBkUpAccess();           // Enable access to backup SRAM
+    // __HAL_RCC_BKPSRAM_CLK_ENABLE();
+    // LL_PWR_EnableBkUpRegulator();         // Enable backup regulator
+    // while (!LL_PWR_IsActiveFlag_BRR());   // Wait until backup regulator is initialized
+  #endif
+
+  HAL_timer_init();
+
+  #if ENABLED(EMERGENCY_PARSER) && USBD_USE_CDC
+    USB_Hook_init();
+  #endif
+
+  TERN_(POSTMORTEM_DEBUGGING, install_min_serial());    // Install the min serial handler
+
+  TERN_(HAS_SD_HOST_DRIVE, MSC_SD_init());              // Enable USB SD card access
+
+  #if PIN_EXISTS(USB_CONNECT)
+    OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
+    delay_ms(1000);                                        // Give OS time to notice
+    WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
+  #endif
+}
+
+uint8_t MarlinHAL::get_reset_source() {
+  return watchdog_enable_caused_reboot() ? RST_WATCHDOG : 0;
+}
+
+void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
+
+// ------------------------
+// Watchdog Timer
+// ------------------------
+
+#if ENABLED(USE_WATCHDOG)
+
+  #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
+
+  extern "C" {
+    #include "hardware/watchdog.h"
+  }
+
+  void MarlinHAL::watchdog_init() {
+    #if DISABLED(DISABLE_WATCHDOG_INIT)
+      static_assert(WDT_TIMEOUT_US > 1000, "WDT Timout is too small, aborting");
+      watchdog_enable(WDT_TIMEOUT_US/1000, true);
+    #endif
+  }
+
+  void MarlinHAL::watchdog_refresh() {
+    watchdog_update();
+    #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
+      TOGGLE(LED_PIN);  // heartbeat indicator
+    #endif
+  }
+
+#endif
+
+// ------------------------
+// ADC
+// ------------------------
+
+volatile bool MarlinHAL::adc_has_result = false;
+
+void MarlinHAL::adc_init() {
+  analogReadResolution(HAL_ADC_RESOLUTION);
+  ::adc_init();
+  adc_fifo_setup(true, false, 1, false, false);
+  irq_set_exclusive_handler(ADC_IRQ_FIFO, adc_exclusive_handler);
+  irq_set_enabled(ADC_IRQ_FIFO, true);
+  adc_irq_set_enabled(true);
+}
+
+void MarlinHAL::adc_enable(const pin_t pin) {
+  if (pin >= A0 && pin <= A3)
+    adc_gpio_init(pin);
+  else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN)
+    adc_set_temp_sensor_enabled(true);
+}
+
+void MarlinHAL::adc_start(const pin_t pin) {
+  adc_has_result = false;
+  // Select an ADC input. 0...3 are GPIOs 26...29 respectively.
+  adc_select_input(pin == HAL_ADC_MCU_TEMP_DUMMY_PIN ? 4 : pin - A0);
+  adc_run(true);
+}
+
+void MarlinHAL::adc_exclusive_handler() {
+  adc_run(false); // Disable since we only want one result
+  irq_clear(ADC_IRQ_FIFO); // Clear the IRQ
+
+  if (adc_fifo_get_level() >= 1) {
+    adc_result = adc_fifo_get(); // Pop the result
+    adc_fifo_drain();
+    adc_has_result = true; // Signal the end of the conversion
+  }
+}
+
+uint16_t MarlinHAL::adc_value() { return adc_result; }
+
+// Reset the system to initiate a firmware flash
+void flashFirmware(const int16_t) { hal.reboot(); }
+
+extern "C" {
+  void * _sbrk(int incr);
+  extern unsigned int __bss_end__; // end of bss section
+}
+
+// Return free memory between end of heap (or end bss) and whatever is current
+int freeMemory() {
+  int free_memory, heap_end = (int)_sbrk(0);
+  return (int)&free_memory - (heap_end ?: (int)&__bss_end__);
+}
+
+#endif // __PLAT_RP2040__

+ 250 - 0
Marlin/src/HAL/RP2040/HAL.h

@@ -0,0 +1,250 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#define CPU_32_BIT
+
+#ifndef F_CPU
+  #define F_CPU (XOSC_MHZ * 1000000UL)
+#endif
+
+#include "arduino_extras.h"
+#include "../../core/macros.h"
+#include "../shared/Marduino.h"
+#include "../shared/math_32bit.h"
+#include "../shared/HAL_SPI.h"
+#include "fastio.h"
+//#include "Servo.h"
+#include "watchdog.h"
+#include "MarlinSerial.h"
+
+#include "../../inc/MarlinConfigPre.h"
+
+#include <stdint.h>
+
+// ------------------------
+// Serial ports
+// ------------------------
+
+#include "../../core/serial_hook.h"
+typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
+extern DefaultSerial1 MSerial0;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+
+#if SERIAL_PORT == -1
+  #define MYSERIAL1 MSerial0
+#elif WITHIN(SERIAL_PORT, 0, 6)
+  #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+#else
+  #error "SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+#endif
+
+#ifdef SERIAL_PORT_2
+  #if SERIAL_PORT_2 == -1
+    #define MYSERIAL2 MSerial0
+  #elif WITHIN(SERIAL_PORT_2, 0, 6)
+    #define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
+  #else
+    #error "SERIAL_PORT_2 must be from 0 to 6. You can also use -1 if the board supports Native USB."
+  #endif
+#endif
+
+#ifdef SERIAL_PORT_3
+  #if SERIAL_PORT_3 == -1
+    #define MYSERIAL3 MSerial0
+  #elif WITHIN(SERIAL_PORT_3, 0, 6)
+    #define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
+  #else
+    #error "SERIAL_PORT_3 must be from 0 to 6. You can also use -1 if the board supports Native USB."
+  #endif
+#endif
+
+#ifdef MMU2_SERIAL_PORT
+  #if MMU2_SERIAL_PORT == -1
+    #define MMU2_SERIAL MSerial0
+  #elif WITHIN(MMU2_SERIAL_PORT, 0, 6)
+    #define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
+  #else
+    #error "MMU2_SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+  #endif
+#endif
+
+#ifdef LCD_SERIAL_PORT
+  #if LCD_SERIAL_PORT == -1
+    #define LCD_SERIAL MSerial0
+  #elif WITHIN(LCD_SERIAL_PORT, 0, 6)
+    #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
+  #else
+    #error "LCD_SERIAL_PORT must be from 0 to 6. You can also use -1 if the board supports Native USB."
+  #endif
+  #if HAS_DGUS_LCD
+    #define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
+  #endif
+#endif
+
+// ------------------------
+// Defines
+// ------------------------
+
+/**
+ * TODO: review this to return 1 for pins that are not analog input
+ */
+#ifndef analogInputToDigitalPin
+  #define analogInputToDigitalPin(p) (p)
+#endif
+
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
+#define cli() __disable_irq()
+#define sei() __enable_irq()
+
+// ------------------------
+// Types
+// ------------------------
+
+template <bool, class L, class R> struct IFPIN { typedef R type; };
+template <class L, class R> struct IFPIN<true, L, R> { typedef L type; };
+typedef IFPIN<sizeof(pin_size_t) == 1, int8_t, int16_t>::type pin_t;
+
+class libServo;
+typedef libServo hal_servo_t;
+#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
+#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
+
+// ------------------------
+// ADC
+// ------------------------
+
+#define HAL_ADC_VREF         3.3
+#ifdef ADC_RESOLUTION
+  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
+#else
+  #define HAL_ADC_RESOLUTION 12
+#endif
+// ADC index 4 is the MCU temperature
+#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127
+
+//
+// Pin Mapping for M42, M43, M226
+//
+#define GET_PIN_MAP_PIN(index) index
+#define GET_PIN_MAP_INDEX(pin) pin
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
+
+#ifndef PLATFORM_M997_SUPPORT
+  #define PLATFORM_M997_SUPPORT
+#endif
+void flashFirmware(const int16_t);
+
+// Maple Compatibility
+typedef void (*systickCallback_t)(void);
+void systick_attach_callback(systickCallback_t cb);
+void HAL_SYSTICK_Callback();
+
+extern volatile uint32_t systick_uptime_millis;
+
+#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
+#define PWM_FREQUENCY 1000     // Default PWM frequency when set_pwm_duty() is called without set_pwm_frequency()
+
+// ------------------------
+// Class Utilities
+// ------------------------
+
+int freeMemory();
+
+// ------------------------
+// MarlinHAL Class
+// ------------------------
+
+class MarlinHAL {
+public:
+
+  // Earliest possible init, before setup()
+  MarlinHAL() {}
+
+  // Watchdog
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
+
+  static void init();          // Called early in setup()
+  static void init_board() {}  // Called less early in setup()
+  static void reboot();        // Restart the firmware from 0x0
+
+  // Interrupts
+  static bool isr_state() { return !__get_PRIMASK(); }
+  static void isr_on()  { __enable_irq(); }
+  static void isr_off() { __disable_irq(); }
+
+  static void delay_ms(const int ms) { ::delay(ms); }
+
+  // Tasks, called from idle()
+  static void idletask() {}
+
+  // Reset
+  static uint8_t get_reset_source();
+  static void clear_reset_source() {}
+
+  // Free SRAM
+  static int freeMemory() { return ::freeMemory(); }
+
+  //
+  // ADC Methods
+  //
+
+  // Called by Temperature::init once at startup
+  static void adc_init();
+
+  // Called by Temperature::init for each sensor at startup
+  static void adc_enable(const pin_t pin);
+
+  // Begin ADC sampling on the given pin. Called from Temperature::isr!
+  static void adc_start(const pin_t pin);
+
+  // This ADC runs a periodic task
+  static void adc_exclusive_handler();
+
+  // Is the ADC ready for reading?
+  static volatile bool adc_has_result;
+  static bool adc_ready() { return adc_has_result; }
+
+  // The current value of the ADC register
+  static uint16_t adc_value();
+
+  /**
+   * Set the PWM duty cycle for the pin to the given value.
+   * Optionally invert the duty cycle [default = false]
+   * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
+   */
+  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
+
+  /**
+   * Set the frequency of the timer for the given pin as close as
+   * possible to the provided desired frequency. Internally calculate
+   * the required waveform generation mode, prescaler, and resolution
+   * values and set timer registers accordingly.
+   * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
+   * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST_PWM_FAN Settings)
+   */
+  static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
+};

+ 69 - 0
Marlin/src/HAL/RP2040/HAL_MinSerial.cpp

@@ -0,0 +1,69 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(POSTMORTEM_DEBUGGING)
+
+#include "../shared/HAL_MinSerial.h"
+
+
+static void TXBegin() {
+  #if !WITHIN(SERIAL_PORT, -1, 2)
+    #warning "Using POSTMORTEM_DEBUGGING requires a physical U(S)ART hardware in case of severe error."
+    #warning "Disabling the severe error reporting feature currently because the used serial port is not a HW port."
+  #else
+    #if SERIAL_PORT == -1
+      USBSerial.begin(BAUDRATE);
+    #elif SERIAL_PORT == 0
+      USBSerial.begin(BAUDRATE);
+    #elif SERIAL_PORT == 1
+      Serial1.begin(BAUDRATE);
+    #endif
+  #endif
+}
+
+static void TX(char b){
+    #if SERIAL_PORT == -1
+      USBSerial
+    #elif SERIAL_PORT == 0
+      USBSerial
+    #elif SERIAL_PORT == 1
+      Serial1
+    #endif
+    .write(b);
+}
+
+// A SW memory barrier, to ensure GCC does not overoptimize loops
+#define sw_barrier() __asm__ volatile("": : :"memory");
+
+
+void install_min_serial() {
+  HAL_min_serial_init = &TXBegin;
+  HAL_min_serial_out = &TX;
+}
+
+#endif // POSTMORTEM_DEBUGGING
+#endif // __PLAT_RP2040__

+ 228 - 0
Marlin/src/HAL/RP2040/HAL_SPI.cpp

@@ -0,0 +1,228 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#include <SPI.h>
+
+// ------------------------
+// Public Variables
+// ------------------------
+
+static SPISettings spiConfig;
+
+// ------------------------
+// Public functions
+// ------------------------
+
+#if ENABLED(SOFTWARE_SPI)
+
+  // ------------------------
+  // Software SPI
+  // ------------------------
+
+  #include "../shared/Delay.h"
+
+  void spiBegin(void) {
+    OUT_WRITE(SD_SS_PIN, HIGH);
+    OUT_WRITE(SD_SCK_PIN, HIGH);
+    SET_INPUT(SD_MISO_PIN);
+    OUT_WRITE(SD_MOSI_PIN, HIGH);
+  }
+
+  // Use function with compile-time value so we can actually reach the desired frequency
+  // Need to adjust this a little bit: on a 72MHz clock, we have 14ns/clock
+  // and we'll use ~3 cycles to jump to the method and going back, so it'll take ~40ns from the given clock here
+  #define CALLING_COST_NS  (3U * 1000000000U) / (F_CPU)
+  void (*delaySPIFunc)();
+  void delaySPI_125()  { DELAY_NS(125 - CALLING_COST_NS); }
+  void delaySPI_250()  { DELAY_NS(250 - CALLING_COST_NS); }
+  void delaySPI_500()  { DELAY_NS(500 - CALLING_COST_NS); }
+  void delaySPI_1000() { DELAY_NS(1000 - CALLING_COST_NS); }
+  void delaySPI_2000() { DELAY_NS(2000 - CALLING_COST_NS); }
+  void delaySPI_4000() { DELAY_NS(4000 - CALLING_COST_NS); }
+
+  void spiInit(uint8_t spiRate) {
+    // Use datarates Marlin uses
+    switch (spiRate) {
+      case SPI_FULL_SPEED:   delaySPIFunc =  &delaySPI_125; break;  // desired: 8,000,000  actual: ~1.1M
+      case SPI_HALF_SPEED:   delaySPIFunc =  &delaySPI_125; break;  // desired: 4,000,000  actual: ~1.1M
+      case SPI_QUARTER_SPEED:delaySPIFunc =  &delaySPI_250; break;  // desired: 2,000,000  actual: ~890K
+      case SPI_EIGHTH_SPEED: delaySPIFunc =  &delaySPI_500; break;  // desired: 1,000,000  actual: ~590K
+      case SPI_SPEED_5:      delaySPIFunc = &delaySPI_1000; break;  // desired:   500,000  actual: ~360K
+      case SPI_SPEED_6:      delaySPIFunc = &delaySPI_2000; break;  // desired:   250,000  actual: ~210K
+      default:               delaySPIFunc = &delaySPI_4000; break;  // desired:   125,000  actual: ~123K
+    }
+    SPI.begin();
+  }
+
+  // Begin SPI transaction, set clock, bit order, data mode
+  void spiBeginTransaction(uint32_t spiClock, uint8_t bitOrder, uint8_t dataMode) { /* do nothing */ }
+
+  uint8_t HAL_SPI_RP2040_SpiTransfer_Mode_3(uint8_t b) { // using Mode 3
+    for (uint8_t bits = 8; bits--;) {
+      WRITE(SD_SCK_PIN, LOW);
+      WRITE(SD_MOSI_PIN, b & 0x80);
+
+      delaySPIFunc();
+      WRITE(SD_SCK_PIN, HIGH);
+      delaySPIFunc();
+
+      b <<= 1;        // little setup time
+      b |= (READ(SD_MISO_PIN) != 0);
+    }
+    DELAY_NS(125);
+    return b;
+  }
+
+  // Soft SPI receive byte
+  uint8_t spiRec() {
+    hal.isr_off();  // No interrupts during byte receive
+    const uint8_t data = HAL_SPI_RP2040_SpiTransfer_Mode_3(0xFF);
+    hal.isr_on();   // Enable interrupts
+    return data;
+  }
+
+  // Soft SPI read data
+  void spiRead(uint8_t *buf, uint16_t nbyte) {
+    for (uint16_t i = 0; i < nbyte; i++)
+      buf[i] = spiRec();
+  }
+
+  // Soft SPI send byte
+  void spiSend(uint8_t data) {
+    hal.isr_off();                            // No interrupts during byte send
+    HAL_SPI_RP2040_SpiTransfer_Mode_3(data);  // Don't care what is received
+    hal.isr_on();                             // Enable interrupts
+  }
+
+  // Soft SPI send block
+  void spiSendBlock(uint8_t token, const uint8_t *buf) {
+    spiSend(token);
+    for (uint16_t i = 0; i < 512; i++)
+      spiSend(buf[i]);
+  }
+
+#else
+
+  // ------------------------
+  // Hardware SPI
+  // ------------------------
+
+  /**
+   * VGPV SPI speed start and PCLK2/2, by default 108/2 = 54Mhz
+   */
+
+  /**
+   * @brief  Begin SPI port setup
+   *
+   * @return Nothing
+   *
+   * @details Only configures SS pin since stm32duino creates and initialize the SPI object
+   */
+  void spiBegin() {
+    #if PIN_EXISTS(SD_SS)
+      OUT_WRITE(SD_SS_PIN, HIGH);
+    #endif
+  }
+
+  // Configure SPI for specified SPI speed
+  void spiInit(uint8_t spiRate) {
+    // Use datarates Marlin uses
+    uint32_t clock;
+    switch (spiRate) {
+      case SPI_FULL_SPEED:    clock = 20000000; break; // 13.9mhz=20000000  6.75mhz=10000000  3.38mhz=5000000  .833mhz=1000000
+      case SPI_HALF_SPEED:    clock =  5000000; break;
+      case SPI_QUARTER_SPEED: clock =  2500000; break;
+      case SPI_EIGHTH_SPEED:  clock =  1250000; break;
+      case SPI_SPEED_5:       clock =   625000; break;
+      case SPI_SPEED_6:       clock =   300000; break;
+      default:
+        clock = 4000000; // Default from the SPI library
+    }
+    spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
+
+    //SPI.setMISO(SD_MISO_PIN); //todo: implement? bad interface
+    //SPI.setMOSI(SD_MOSI_PIN);
+    //SPI.setSCLK(SD_SCK_PIN);
+
+    SPI.begin();
+  }
+
+  /**
+   * @brief  Receives a single byte from the SPI port.
+   *
+   * @return Byte received
+   *
+   * @details
+   */
+  uint8_t spiRec() {
+    uint8_t returnByte = SPI.transfer(0xFF);
+    return returnByte;
+  }
+
+  /**
+   * @brief  Receive a number of bytes from the SPI port to a buffer
+   *
+   * @param  buf   Pointer to starting address of buffer to write to.
+   * @param  nbyte Number of bytes to receive.
+   * @return Nothing
+   *
+   * @details Uses DMA
+   */
+  void spiRead(uint8_t *buf, uint16_t nbyte) {
+    if (nbyte == 0) return;
+    memset(buf, 0xFF, nbyte);
+    SPI.transfer(buf, nbyte);
+  }
+
+  /**
+   * @brief  Send a single byte on SPI port
+   *
+   * @param  b Byte to send
+   *
+   * @details
+   */
+  void spiSend(uint8_t b) {
+    SPI.transfer(b);
+  }
+
+  /**
+   * @brief  Write token and then write from 512 byte buffer to SPI (for SD card)
+   *
+   * @param  buf   Pointer with buffer start address
+   * @return Nothing
+   *
+   * @details Use DMA
+   */
+  void spiSendBlock(uint8_t token, const uint8_t *buf) {
+    //uint8_t rxBuf[512];
+    //SPI.transfer(token);
+    SPI.transfer((uint8_t*)buf, 512); //implement? bad interface
+  }
+
+#endif // SOFTWARE_SPI
+
+#endif // __PLAT_RP2040__

+ 39 - 0
Marlin/src/HAL/RP2040/MarlinSerial.cpp

@@ -0,0 +1,39 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+#include "MarlinSerial.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+  #include "../../feature/e_parser.h"
+#endif
+
+#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
+#define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
+#if WITHIN(SERIAL_PORT, 0, 3)
+  IMPLEMENT_SERIAL(SERIAL_PORT);
+#endif
+
+#endif // __PLAT_RP2040__

+ 52 - 0
Marlin/src/HAL/RP2040/MarlinSerial.h

@@ -0,0 +1,52 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#include "../../inc/MarlinConfigPre.h"
+
+#if ENABLED(EMERGENCY_PARSER)
+  #include "../../feature/e_parser.h"
+#endif
+
+#include "../../core/serial_hook.h"
+
+#define Serial0 Serial
+#define _DECLARE_SERIAL(X) \
+  typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
+  extern DefaultSerial##X MSerial##X
+#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
+
+typedef ForwardSerial1Class<decltype(SerialUSB)> USBSerialType;
+extern USBSerialType USBSerial;
+
+#define _MSERIAL(X) MSerial##X
+#define MSERIAL(X) _MSERIAL(X)
+
+#if SERIAL_PORT == -1
+ // #define MYSERIAL1 USBSerial this is already done in the HAL
+#elif WITHIN(SERIAL_PORT, 0, 3)
+ #define MYSERIAL1 MSERIAL(SERIAL_PORT)
+  DECLARE_SERIAL(SERIAL_PORT);
+#else
+  #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
+#endif
+

+ 1 - 0
Marlin/src/HAL/RP2040/README.md

@@ -0,0 +1 @@
+# RP2040 Hardware Interface

+ 93 - 0
Marlin/src/HAL/RP2040/Servo.cpp

@@ -0,0 +1,93 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program 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 program 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 this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#include "../platforms.h"
+
+#ifdef __PLAT_RP2040__
+
+#include "../../inc/MarlinConfig.h"
+
+#if HAS_SERVOS
+
+#include "Servo.h"
+
+static uint_fast8_t servoCount = 0;
+static libServo *servos[NUM_SERVOS] = {0};
+constexpr millis_t servoDelay[] = SERVO_DELAY;
+static_assert(COUNT(servoDelay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
+
+libServo::libServo()
+: delay(servoDelay[servoCount]),
+  was_attached_before_pause(false),
+  value_before_pause(0)
+{
+  servos[servoCount++] = this;
+}
+
+int8_t libServo::attach(const int pin) {
+  if (servoCount >= MAX_SERVOS) return -1;
+  if (pin > 0) servo_pin = pin;
+  auto result = pico_servo.attach(servo_pin);
+  return result;
+}
+
+int8_t libServo::attach(const int pin, const int min, const int max) {
+  if (servoCount >= MAX_SERVOS) return -1;
+  if (pin > 0) servo_pin = pin;
+  auto result = pico_servo.attach(servo_pin, min, max);
+  return result;
+}
+
+void libServo::move(const int value) {
+  if (attach(0) >= 0) {
+    pico_servo.write(value);
+    safe_delay(delay);
+    TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
+  }
+}
+
+void libServo::pause() {
+  was_attached_before_pause = pico_servo.attached();
+  if (was_attached_before_pause) {
+    value_before_pause = pico_servo.read();
+    pico_servo.detach();
+  }
+}
+
+void libServo::resume() {
+  if (was_attached_before_pause) {
+    attach();
+    move(value_before_pause);
+  }
+}
+
+void libServo::pause_all_servos() {
+  for (auto& servo : servos)
+    if (servo) servo->pause();
+}
+
+void libServo::resume_all_servos() {
+  for (auto& servo : servos)
+    if (servo) servo->resume();
+}
+
+#endif // HAS_SERVOS
+#endif // __PLAT_RP2040__

Some files were not shown because too many files changed in this diff