diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp index e8d0eea7cd..9341480078 100644 --- a/Marlin/src/HAL/RP2040/HAL.cpp +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -32,17 +32,123 @@ extern "C" { #include "pico/bootrom.h" #include "hardware/watchdog.h" + #include "pico/multicore.h" + #include "hardware/adc.h" + #include "pico/time.h" } #if HAS_SD_HOST_DRIVE #include "msc_sd.h" - #include "usbd_cdc_if.h" #endif +// Core 1 watchdog configuration +#define CORE1_MAX_RESETS 5 // Maximum number of Core 1 resets before halting system + // ------------------------ // Public Variables // ------------------------ +volatile uint32_t adc_accumulators[5] = {0}; // Accumulators for oversampling (sum of readings) +volatile uint8_t adc_counts[5] = {0}; // Count of readings accumulated per channel +volatile uint16_t adc_values[5] = {512, 512, 512, 512, 512}; // Final oversampled ADC values (averages) - initialized to mid-range + +// Core 1 watchdog monitoring +volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity +volatile bool core1_watchdog_triggered = false; // Flag to indicate Core 1 reset +volatile uint8_t core1_reset_count = 0; // Count of Core 1 resets - halt system if >= CORE1_MAX_RESETS +volatile uint8_t current_pin; +volatile bool MarlinHAL::adc_has_result; +volatile uint8_t adc_channels_enabled[5] = {false}; // Track which ADC channels are enabled + +// Helper function for LED blinking patterns +void blink_led_pattern(uint8_t blink_count, uint32_t blink_duration_us = 100000) { + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + for (uint8_t i = 0; i < blink_count; i++) { + WRITE(LED_PIN, HIGH); + busy_wait_us(blink_duration_us); + WRITE(LED_PIN, LOW); + if (i < blink_count - 1) { // Don't delay after the last blink + busy_wait_us(blink_duration_us); + } + } + #endif +} + +// Core 1 ADC reading task - dynamically reads all enabled channels with oversampling +void core1_adc_task() { + static uint32_t last_led_toggle = 0; + const uint8_t OVERSAMPLENR = 16; // Standard Marlin oversampling count + + // Signal successful Core 1 startup/restart + SERIAL_ECHO_MSG("Core 1 ADC task started"); + + while (true) { + // Update heartbeat timestamp at start of each scan cycle + core1_last_heartbeat = time_us_32(); + + // Scan all enabled ADC channels + for (uint8_t channel = 0; channel < 5; channel++) { + if (!adc_channels_enabled[channel]) continue; + + // Enable temperature sensor if reading channel 4 + if (channel == 4) { + adc_set_temp_sensor_enabled(true); + } + + // Select and read the channel + adc_select_input(channel); + busy_wait_us(100); // Settling delay + adc_fifo_drain(); + adc_run(true); + + // Wait for conversion with timeout + uint32_t timeout = 10000; + while (adc_fifo_is_empty() && timeout--) { + busy_wait_us(1); + } + + adc_run(false); + uint16_t reading = adc_fifo_is_empty() ? 0 : adc_fifo_get(); + + // Accumulate readings for oversampling + adc_accumulators[channel] += reading; + adc_counts[channel]++; + + // Update the averaged value with current accumulation (provides immediate valid data) + adc_values[channel] = adc_accumulators[channel] / adc_counts[channel]; + + // When we reach the full oversampling count, reset accumulator for next cycle + if (adc_counts[channel] >= OVERSAMPLENR) { + adc_accumulators[channel] = 0; + adc_counts[channel] = 0; + } + + // Disable temp sensor after reading to save power + if (channel == 4) { + adc_set_temp_sensor_enabled(false); + } + } + + // Core 1 LED indicator: Double blink every 2 seconds to show Core 1 is active + uint32_t now = time_us_32(); + if (now - last_led_toggle >= 2000000) { // 2 seconds + last_led_toggle = now; + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + // Triple blink pattern if watchdog was triggered (shows Core 1 was reset) + if (core1_watchdog_triggered) { + core1_watchdog_triggered = false; // Clear flag + blink_led_pattern(3); // Triple blink for watchdog reset + } else { + blink_led_pattern(2); // Normal double blink + } + #endif + } + + // Delay between full scan cycles + busy_wait_us(10000); // 10ms between scans + } +} + volatile uint16_t adc_result; // ------------------------ @@ -118,9 +224,28 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } } void MarlinHAL::watchdog_refresh() { + // If Core 1 has reset CORE1_MAX_RESETS+ times, stop updating watchdog to halt system + if (core1_reset_count >= CORE1_MAX_RESETS) { + SERIAL_ECHO_MSG("Core 1 reset limit exceeded (", core1_reset_count, " resets) - halting system for safety"); + return; // Don't update watchdog - system will halt + } + watchdog_update(); + + // Check Core 1 watchdog (15 second timeout) + uint32_t now = time_us_32(); + if (now - core1_last_heartbeat > 15000000) { // 15 seconds + // Core 1 appears stuck - reset it + multicore_reset_core1(); + multicore_launch_core1(core1_adc_task); + core1_watchdog_triggered = true; // Signal for LED indicator + core1_reset_count++; // Increment reset counter + SERIAL_ECHO_MSG("Core 1 ADC watchdog triggered - resetting Core 1 (attempt ", core1_reset_count, ")"); + } + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - TOGGLE(LED_PIN); // heartbeat indicator + // Core 0 LED indicator: Single toggle every watchdog refresh (shows Core 0 activity) + TOGGLE(LED_PIN); #endif } @@ -130,43 +255,35 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } // 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); + // Launch Core 1 for continuous ADC reading + multicore_launch_core1(core1_adc_task); + adc_has_result = true; // Results are always available with continuous sampling } void MarlinHAL::adc_enable(const pin_t pin) { - if (pin >= A0 && pin <= A3) + 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 + adc_channels_enabled[pin - A0] = true; // Mark this channel as enabled + } + else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) { + adc_channels_enabled[4] = true; // Mark MCU temp channel as enabled } } -uint16_t MarlinHAL::adc_value() { return adc_result; } +void MarlinHAL::adc_start(const pin_t pin) { + // Just store which pin we need to read - values are continuously updated by Core 1 + current_pin = pin; +} + +uint16_t MarlinHAL::adc_value() { + // Return the latest ADC value from Core 1's continuous readings + const uint8_t channel = (current_pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) ? 4 : (current_pin - A0); + return adc_values[channel]; +} // Reset the system to initiate a firmware flash void flashFirmware(const int16_t) { hal.reboot(); } diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h index 11472f72f5..206847053b 100644 --- a/Marlin/src/HAL/RP2040/HAL.h +++ b/Marlin/src/HAL/RP2040/HAL.h @@ -40,6 +40,11 @@ #include "msc_sd.h" #endif +// ADC index 4 is the MCU temperature +#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127 +#define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN // ADC4 is internal temp sensor +#include "temp_soc.h" + // // Serial Ports // @@ -85,8 +90,6 @@ typedef libServo hal_servo_t; #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 @@ -164,9 +167,6 @@ public: // 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; } diff --git a/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp index 89e882d77b..bf52109173 100644 --- a/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp +++ b/Marlin/src/HAL/RP2040/eeprom/eeprom_flash.cpp @@ -31,28 +31,48 @@ // NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module -// Use EEPROM.h for compatibility, for now. -#include +// RP2040 Flash-based EEPROM emulation using internal flash memory +#include +#include -static bool eeprom_data_written = false; +// Flash sector size is already defined in hardware/flash.h as FLASH_SECTOR_SIZE +// Place EEPROM emulation at the end of flash, before the filesystem +// This assumes 2MB flash, adjust if using different flash size +#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE) #ifndef MARLIN_EEPROM_SIZE #define MARLIN_EEPROM_SIZE size_t(E2END + 1) #endif + +static uint8_t eeprom_buffer[MARLIN_EEPROM_SIZE]; +static bool eeprom_data_written = false; +static bool eeprom_initialized = false; size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } bool PersistentStore::access_start() { - EEPROM.begin(); // Avoid EEPROM.h warning (do nothing) - eeprom_buffer_fill(); + if (!eeprom_initialized) { + // Read from flash into buffer + const uint8_t *flash_data = (const uint8_t *)(XIP_BASE + FLASH_TARGET_OFFSET); + memcpy(eeprom_buffer, flash_data, MARLIN_EEPROM_SIZE); + eeprom_initialized = true; + } return true; } bool PersistentStore::access_finish() { if (eeprom_data_written) { TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT()); - hal.isr_off(); - eeprom_buffer_flush(); - hal.isr_on(); + + // Disable interrupts during flash write + const uint32_t intstate = save_and_disable_interrupts(); + + // Erase and program the sector + flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE); + flash_range_program(FLASH_TARGET_OFFSET, eeprom_buffer, MARLIN_EEPROM_SIZE); + + // Restore interrupts + restore_interrupts(intstate); + TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT()); eeprom_data_written = false; } @@ -62,8 +82,8 @@ bool PersistentStore::access_finish() { bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { while (size--) { uint8_t v = *value; - if (v != eeprom_buffered_read_byte(pos)) { - eeprom_buffered_write_byte(pos, v); + if (pos < (int)MARLIN_EEPROM_SIZE && v != eeprom_buffer[pos]) { + eeprom_buffer[pos] = v; eeprom_data_written = true; } crc16(crc, &v, 1); @@ -75,7 +95,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) { do { - const uint8_t c = eeprom_buffered_read_byte(pos); + const uint8_t c = (pos < (int)MARLIN_EEPROM_SIZE) ? eeprom_buffer[pos] : 0xFF; if (writing) *value = c; crc16(crc, &c, 1); pos++; diff --git a/Marlin/src/HAL/RP2040/pinsDebug.h b/Marlin/src/HAL/RP2040/pinsDebug.h index f3842c4aff..8f58089fb1 100644 --- a/Marlin/src/HAL/RP2040/pinsDebug.h +++ b/Marlin/src/HAL/RP2040/pinsDebug.h @@ -25,7 +25,7 @@ #include "HAL.h" #ifndef NUM_DIGITAL_PINS - #error "Expected NUM_DIGITAL_PINS not found" + #error "Expected NUM_DIGITAL_PINS not found." #endif /** @@ -74,6 +74,27 @@ * signal. The Arduino pin number is listed by the M43 I command. */ +/** + * Pins Debugging for RP2040 + * + * - NUMBER_PINS_TOTAL + * - MULTI_NAME_PAD + * - getPinByIndex(index) + * - printPinNameByIndex(index) + * - getPinIsDigitalByIndex(index) + * - digitalPinToAnalogIndex(pin) + * - getValidPinMode(pin) + * - isValidPin(pin) + * - isAnalogPin(pin) + * - digitalRead_mod(pin) + * - pwm_status(pin) + * - printPinPWM(pin) + * - printPinPort(pin) + * - printPinNumber(pin) + * - printPinAnalog(pin) + */ + +#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS #define NUM_ANALOG_FIRST A0 #define MODE_PIN_INPUT 0 // Input mode (reset state) @@ -81,66 +102,66 @@ #define MODE_PIN_ALT 2 // Alternate function mode #define MODE_PIN_ANALOG 3 // Analog mode -#define PIN_NUM(P) (P & 0x000F) -#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1') -#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 ) -#define PORT_NUM(P) ((P >> 4) & 0x0007) -#define PORT_ALPHA(P) ('A' + (P >> 4)) +#define getPinByIndex(x) pin_array[x].pin +#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) +#define getPinIsDigitalByIndex(x) pin_array[x].is_digital +#define digitalPinToAnalogIndex(P) digital_pin_to_analog_pin(P) -/** - * Translation of routines & variables used by pinsDebug.h - */ -#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS -#define VALID_PIN(ANUM) (pin_t(ANUM) >= 0 && pin_t(ANUM) < NUMBER_PINS_TOTAL) -#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads -#define PRINT_PIN(Q) -#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0) -#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine +uint8_t get_pin_mode(const pin_t pin) { + // Check if pin is in alternate function mode (I2C, SPI, etc.) + const uint32_t gpio_func = gpio_get_function(pin); -// x is a variable used to search pin_array -#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital) -#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin) -#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) -#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin - -uint8_t get_pin_mode(const pin_t Ard_num) { - - uint dir = gpio_get_dir( Ard_num); - - if (dir) return MODE_PIN_OUTPUT; - else return MODE_PIN_INPUT; + // GPIO_FUNC_I2C is typically function 3 on RP2040 + if ( gpio_func == GPIO_FUNC_I2C + || gpio_func == GPIO_FUNC_SPI + || gpio_func == GPIO_FUNC_UART + || gpio_func == GPIO_FUNC_PWM + ) { + return MODE_PIN_ALT; + } + // For GPIO mode, check direction + return gpio_get_dir(pin) ? MODE_PIN_OUTPUT : MODE_PIN_INPUT; } -bool getValidPinMode(const pin_t Ard_num) { - const uint8_t pin_mode = get_pin_mode(Ard_num); +bool getValidPinMode(const pin_t pin) { + const uint8_t pin_mode = get_pin_mode(pin); return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM } -int8_t digital_pin_to_analog_pin(pin_t Ard_num) { - Ard_num -= NUM_ANALOG_FIRST; - return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1; +#define isValidPin(P) WITHIN(P, 0, pin_t(NUMBER_PINS_TOTAL - 1)) + +int8_t digital_pin_to_analog_pin(pin_t pin) { + pin -= NUM_ANALOG_FIRST; + return (WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) ? pin : -1; } -bool isAnalogPin(const pin_t Ard_num) { - return digital_pin_to_analog_pin(Ard_num) != -1; +bool isAnalogPin(const pin_t pin) { + return digital_pin_to_analog_pin(pin) != -1; } -bool is_digital(const pin_t x) { - const uint8_t pin_mode = get_pin_mode(x); - return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads +#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0) +#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) +#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin + +//bool is_digital(const pin_t pin) { +// const uint8_t pin_mode = get_pin_mode(pin); +// return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT; +//} + +bool pwm_status(const pin_t pin) { + // Check if this pin is configured for PWM + return PWM_PIN(pin) && get_pin_mode(pin) == MODE_PIN_ALT; } -void printPinPort(const pin_t Ard_num) { - SERIAL_ECHOPGM("Pin: "); - SERIAL_ECHO(Ard_num); -} - -bool pwm_status(const pin_t Ard_num) { - return get_pin_mode(Ard_num) == MODE_PIN_ALT; -} - -void printPinPWM(const pin_t Ard_num) { - if (PWM_PIN(Ard_num)) { +void printPinPWM(const pin_t pin) { + if (pwm_status(pin)) { + // RP2040 has hardware PWM on specific pins + char buffer[22]; + sprintf_P(buffer, PSTR("PWM: pin %d "), pin); + SERIAL_ECHO(buffer); } } + +void printPinPort(const pin_t pin) {} diff --git a/Marlin/src/HAL/RP2040/temp_soc.h b/Marlin/src/HAL/RP2040/temp_soc.h new file mode 100644 index 0000000000..e182fb88dc --- /dev/null +++ b/Marlin/src/HAL/RP2040/temp_soc.h @@ -0,0 +1,30 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 . + * + */ +#pragma once + +// RP2040 internal temperature sensor +// Formula: T = 27 - (ADC_voltage - 0.706) / 0.001721 +// ADC_voltage = (RAW / OVERSAMPLENR) * 3.3 / 4096 (RAW is accumulated over OVERSAMPLENR samples) +// T = 27 - ((RAW / OVERSAMPLENR) * 3.3 / 4096 - 0.706) / 0.001721 +// Simplified: T = 437.423 - (RAW / OVERSAMPLENR) * 0.46875 + +#define TEMP_SOC_SENSOR(RAW) (437.423f - ((RAW) / OVERSAMPLENR) * 0.46875f) diff --git a/Marlin/src/HAL/RP2040/u8g/LCD_defines.h b/Marlin/src/HAL/RP2040/u8g/LCD_defines.h new file mode 100644 index 0000000000..acdd94b477 --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/LCD_defines.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 . + * + */ +#pragma once + +/** + * RP2040 LCD-specific defines + */ +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_rp2040_ssd_i2c.cpp +#define U8G_COM_SSD_I2C_HAL u8g_com_rp2040_ssd_i2c_fn diff --git a/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp new file mode 100644 index 0000000000..ea42bf190d --- /dev/null +++ b/Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp @@ -0,0 +1,108 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 . + * + */ + +/** + * 2-Wire I2C COM Driver + * + * Handles Hardware I2C on valid pin combinations. + * Wire library is used for Hardware I2C. + * + * Hardware I2C uses pins defined in pins_arduino.h. + */ + +#ifdef __PLAT_RP2040__ + +#include "../../../inc/MarlinConfig.h" + +#if HAS_U8GLIB_I2C_OLED + +#include + +#include +#ifndef MASTER_ADDRESS + #define MASTER_ADDRESS 0x01 +#endif + +/** + * BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h + * Default value is 32 + * Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block + */ +#ifndef BUFFER_LENGTH + #define BUFFER_LENGTH 32 +#endif +#if BUFFER_LENGTH > 144 + #error "BUFFER_LENGTH should not be greater than 144." +#endif +#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1) + +uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) { + + // Hardware I2C flag + //static bool i2c_initialized = false; // Flag to only run init/linking code once + //if (!i2c_initialized) { // Init runtime linkages + // i2c_initialized = true; // Only do this once + //} + + static uint8_t control; + // Use the global Wire instance (already initialized with correct pins for RP2040) + switch (msg) { + case U8G_COM_MSG_INIT: + Wire.setClock(400000); + // Wire already initialized in MarlinUI::init(), no need to call begin() again + break; + + case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1) + control = arg_val ? 0x40 : 0x00; + break; + + case U8G_COM_MSG_WRITE_BYTE: + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + ::Wire.write(arg_val); + ::Wire.endTransmission(); + break; + + case U8G_COM_MSG_WRITE_SEQ: { + uint8_t* dataptr = (uint8_t*)arg_ptr; + while (arg_val > 0) { + ::Wire.beginTransmission(0x3C); + ::Wire.write(control); + if (arg_val <= I2C_MAX_LENGTH) { + ::Wire.write(dataptr, arg_val); + arg_val = 0; + } + else { + ::Wire.write(dataptr, I2C_MAX_LENGTH); + arg_val -= I2C_MAX_LENGTH; + dataptr += I2C_MAX_LENGTH; + } + ::Wire.endTransmission(); + } + break; + } + } + return 1; +} + +#endif // HAS_U8GLIB_I2C_OLED +#endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index b14c9c721c..89e2514af0 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -136,10 +136,8 @@ const XrefInfo pin_xref[] PROGMEM = { #define printPinNumber(Q) #define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0) #define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine - -// x is a variable used to search pin_array -#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital) -#define getPinByIndex(x) ((pin_t) pin_array[x].pin) +#define getPinIsDigitalByIndex(x) bool(pin_array[x].is_digital) +#define getPinByIndex(x) pin_t(pin_array[x].pin) #define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0) #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin @@ -229,8 +227,7 @@ void printPinPort(const pin_t pin) { calc_p -= NUM_ANALOG_FIRST; if (calc_p > 7) calc_p += 8; } - SERIAL_ECHOPGM(" M42 P", calc_p); - SERIAL_CHAR(' '); + SERIAL_ECHO(F(" M42 P"), calc_p, C(' ')); if (calc_p < 100) { SERIAL_CHAR(' '); if (calc_p < 10) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index f22c9fd1f1..6c51cb01a4 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -578,7 +578,8 @@ // #define BOARD_RP2040 6200 // Generic RP2040 Test board -#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x +#define BOARD_RASPBERRY_PI_PICO 6201 // Raspberry Pi Pico +#define BOARD_BTT_SKR_PICO 6202 // BigTreeTech SKR Pico 1.x // // Custom board diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index f4d4c28fa7..8a6d18dc2d 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -260,7 +260,11 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; void MarlinUI::init() { #if HAS_U8GLIB_I2C_OLED && PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM) - Wire.begin(uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)); + #ifdef TARGET_RP2040 + Wire.begin(); // RP2040 MbedI2C uses pins configured in pins_arduino.h + #else + Wire.begin(uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)); + #endif #endif init_lcd(); diff --git a/Marlin/src/pins/mega/pins_GT2560_V3.h b/Marlin/src/pins/mega/pins_GT2560_V3.h index ae4614eedd..81774006df 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V3.h +++ b/Marlin/src/pins/mega/pins_GT2560_V3.h @@ -162,8 +162,9 @@ #endif // -// LCD Controller +// LCD / Controller // + #define BEEPER_PIN 18 #if ENABLED(YHCB2004) diff --git a/Marlin/src/pins/mega/pins_INTAMSYS40.h b/Marlin/src/pins/mega/pins_INTAMSYS40.h index 83a77ec98c..cfb4d0186e 100644 --- a/Marlin/src/pins/mega/pins_INTAMSYS40.h +++ b/Marlin/src/pins/mega/pins_INTAMSYS40.h @@ -116,7 +116,7 @@ #endif // -// LCD Controller +// LCD / Controller // #define BEEPER_PIN 18 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index e73a00ae81..56c4b78dff 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -949,6 +949,8 @@ #elif MB(RP2040) #include "rp2040/pins_RP2040.h" // RP2040 env:RP2040 +#elif MB(RASPBERRY_PI_PICO) + #include "rp2040/pins_RASPBERRY_PI_PICO.h" // RP2040 env:RP2040 #elif MB(BTT_SKR_PICO) #include "rp2040/pins_BTT_SKR_Pico.h" // RP2040 env:SKR_Pico env:SKR_Pico_UART diff --git a/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h b/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h new file mode 100644 index 0000000000..daede9f560 --- /dev/null +++ b/Marlin/src/pins/rp2040/pins_RASPBERRY_PI_PICO.h @@ -0,0 +1,171 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 . + * + */ +#pragma once + +#include "env_validate.h" + +#define BOARD_INFO_NAME "Pi Pico" +#define DEFAULT_MACHINE_NAME "Pi Pico" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000U // 4K + #define FLASH_EEPROM_EMULATION +#endif + +// +// Limit Switches +// +#define X_STOP_PIN 0 // GP0 +#define Y_STOP_PIN 1 // GP1 +#define Z_STOP_PIN 2 // GP2 + +// +// Steppers +// +#define X_STEP_PIN 3 // GP3 +#define X_DIR_PIN 6 // GP6 +#define X_ENABLE_PIN 7 // GP7 + +#define Y_STEP_PIN 8 // GP8 +#define Y_DIR_PIN 9 // GP9 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN 10 // GP10 +#define Z_DIR_PIN 11 // GP11 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN 12 // GP12 +#define E0_DIR_PIN 13 // GP13 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Heaters / Fans +// +#define HEATER_0_PIN 14 // GP14 +#define HEATER_BED_PIN 15 // GP15 +#define FAN0_PIN 28 // GP28 + +// +// Temperature Sensors +// +#define TEMP_0_PIN A0 // GP26 - Analog Input +#define TEMP_BED_PIN A1 // GP27 - Analog Input + +// +// Misc. Functions +// +#define LED_PIN 25 // GP25 + +// +// SD Card +// +#define SD_DETECT_PIN -1 // No pins left +#define SDCARD_CONNECTION ONBOARD +#define SD_SS_PIN 17 // GP17 - SPI0_CS for SD card chip select + +// +// LCD / Controller +// + +#if ENABLED(U8GLIB_SSD1306) + #if !IS_ULTIPANEL + #error "Add '#define IS_ULTIPANEL 1' to Configuration.h to enable Marlin UI menus and encoder support." + #endif + #if IS_NEWPANEL + #define BTN_EN1 20 // GP20 - Encoder A phase + #define BTN_EN2 21 // GP21 - Encoder B phase + #define BTN_ENC 22 // GP22 - Encoder push button + #endif + + #define ALTERNATIVE_LCD // Use default hardware I2C port +#endif // U8GLIB_SSD1306 + +/* +┌───────────────────────────────────────────────────────────────────────────────────────────────────────────┐ +│ RASPBERRY PI PICO - PHYSICAL PIN MAPPING │ +├──────────────┬───────────┬───────────┬───────────┬───────────┬────────────────────────────────────────────┤ +│ Physical Pin │ GPIO │ ALT0 │ ALT1 │ ALT2 │ Marlin Usage │ +├──────────────┼───────────┼───────────┼───────────┼───────────┼────────────────────────────────────────────┤ +│ 1 │ GP0 │ I2C0_SDA │ SPI0_MISO │ UART0_TX │ X_STOP_PIN │ +│ 2 │ GP1 │ I2C0_SCL │ SPI0_CS │ UART0_RX │ Y_STOP_PIN │ +│ 3 │ GND │ │ │ │ │ +│ 4 │ GP2 │ I2C1_SDA │ SPI0_SCK │ │ Z_STOP_PIN │ +│ 5 │ GP3 │ I2C1_SCL │ SPI0_MOSI │ │ X_STEP_PIN │ +│ 6 │ GP4 │ I2C0_SDA │ SPI0_MISO │ UART1_TX │ SDA_PIN │ +│ 7 │ GP5 │ I2C0_SCL │ SPI0_CS │ UART1_RX │ SCL_PIN │ +│ 8 │ GND │ │ │ │ │ +│ 9 │ GP6 │ I2C1_SDA │ SPI0_SCK │ │ X_DIR_PIN │ +│ 10 │ GP7 │ I2C1_SCL │ SPI0_MOSI │ │ X_ENABLE_PIN │ +│ 11 │ GP8 │ I2C0_SDA │ SPI1_MISO │ UART1_TX │ Y_STEP_PIN │ +│ 12 │ GP9 │ I2C0_SCL │ SPI1_CS │ UART1_RX │ Y_DIR_PIN │ +│ 13 │ GND │ │ │ │ │ +│ 14 │ GP10 │ I2C1_SDA │ SPI1_SCK │ │ Z_STEP_PIN │ +│ 15 │ GP11 │ I2C1_SCL │ SPI1_MOSI │ │ Z_DIR_PIN │ +│ 16 │ GP12 │ I2C0_SDA │ SPI1_MISO │ UART0_TX │ E0_STEP_PIN │ +│ 17 │ GP13 │ I2C0_SCL │ SPI1_CS │ UART0_RX │ E0_DIR_PIN │ +│ 18 │ GND │ │ │ │ │ +│ 19 │ GP14 │ I2C1_SDA │ SPI1_SCK │ │ HEATER_0_PIN │ +│ 20 │ GP15 │ I2C1_SCL │ SPI1_MOSI │ │ HEATER_BED_PIN │ +│ 21 │ GP16 │ I2C0_SDA │ SPI0_MISO │ UART0_TX │ SD_MISO_PIN │ +│ 22 │ GP17 │ I2C0_SCL │ SPI0_CS │ UART0_RX │ SD_SS_PIN │ +│ 23 │ GND │ │ │ │ │ +│ 24 │ GP18 │ I2C1_SDA │ SPI0_SCK │ │ SD_SCK_PIN │ +│ 25 │ GP19 │ I2C1_SCL │ SPI0_MOSI │ │ SD_MOSI_PIN │ +│ 26 │ GP20 │ I2C0_SDA │ │ │ BTN_EN1 (Encoder A) │ +│ 27 │ GP21 │ I2C0_SCL │ │ │ BTN_EN2 (Encoder B) │ +│ 28 │ GND │ │ │ │ │ +│ 29 │ GP22 │ │ │ │ BTN_ENC (Encoder Button) │ +│ 30 │ RUN │ │ │ │ Reset (Active Low) │ +│ 31 │ GP26 │ ADC0 │ I2C1_SDA │ │ TEMP_0_PIN (A0) │ +│ 32 │ GP27 │ ADC1 │ I2C1_SCL │ │ TEMP_BED_PIN (A1) │ +│ 33 │ GND │ │ │ │ │ +│ 34 │ GP28 │ ADC2 │ │ │ FAN0_PIN │ +│ 35 │ ADC_VREF│ │ │ │ ADC Reference Voltage │ +│ 36 │ 3V3 │ │ │ │ 3.3V Power Output │ +│ 37 │ 3V3_EN │ │ │ │ 3.3V Enable (Active High) │ +│ 38 │ GND │ │ │ │ │ +│ 39 │ VSYS │ │ │ │ System Voltage Input (1.8-5.5V) │ +│ 40 │ VBUS │ │ │ │ USB Bus Voltage (5V when USB connected) │ +├──────────────┴───────────┴───────────┴───────────┴───────────┴────────────────────────────────────────────┤ +│ Special pin notes for Raspberry Pi Pico │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ • GP23 OP Controls the on-board SMPS Power Save pin. Should not be used for other purposes. │ +│ • GP24 IP VBUS sense - high if VBUS is present, else low. Should not be used for other purposes. │ +│ • GP25 OP Connected to user LED. Can be used with board modifications, is not broken out. │ +│ • GP29 IP Used in ADC mode (ADC3) to measure VSYS/3. Should not be used for other purposes. │ +│ • ADC4 (Internal) is connected to the chip's internal temperature sensor. │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ Marlin pin notes │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ Shared enable pins: │ +│ • GP7: X_ENABLE_PIN. All stepper drivers use a shared single enable pin X_ENABLE_PIN for pin conservation │ +│ │ +│ Hardware I2C and SPI configuration: │ +│ These are hardcoded in: │ +│ .platformio/packages/framework-arduino-mbed/variants/RASPBERRY_RASPBERRY_PI_PICO/pins_arduino.h │ +│ • GP4: SDA default: "#define PIN_WIRE_SDA (4u)" │ +│ • GP5: SCL default: "#define PIN_WIRE_SCL (5u)" │ +│ • GP16: MISO default: "#define PIN_SPI_MISO (16u)" │ +│ • GP18: SCK default: "#define PIN_SPI_SCK (18u)" │ +│ • GP19: MOSI default: "#define PIN_SPI_MOSI (19u)" │ +└───────────────────────────────────────────────────────────────────────────────────────────────────────────┘ +*/ diff --git a/Marlin/src/pins/rp2040/pins_RP2040.h b/Marlin/src/pins/rp2040/pins_RP2040.h index 6a4e54f0bd..95de85b4bf 100644 --- a/Marlin/src/pins/rp2040/pins_RP2040.h +++ b/Marlin/src/pins/rp2040/pins_RP2040.h @@ -89,10 +89,7 @@ #define TEMP_2_PIN A2 // Analog Input #define TEMP_BED_PIN A1 // Analog Input -#define TEMP_MCU HAL_ADC_MCU_TEMP_DUMMY_PIN // this is a flag value, don´t change - #define TEMP_CHAMBER_PIN TEMP_1_PIN -#define TEMP_BOARD_PIN TEMP_MCU // SPI for MAX Thermocouple #if !HAS_MEDIA @@ -560,3 +557,28 @@ #endif // IS_NEWPANEL #endif // HAS_WIRED_LCD + +/* +┌───────────────────────────────────────────────────────────────────────────────────────────────────────────────┐ +│ PIN CONFLICTS and ERRORS │ +├───────────────────────────────────────────────────────────────────────────────────────────────────────────────┤ +│ │ +│ VIRTUAL PINS - NOT REAL GPIO: │ +│ • GP40+: E_MUX pins, TMC_SW pins are virtual/extended pins, not physical RP2040 GPIO │ +│ • GP64, GP66: TMC Software SPI pins - these don't exist on RP2040 hardware │ +│ │ +│ MULTIPLE ASSIGNMENTS - REVIEW NEEDED: │ +│ • GP4: Z_DIR_PIN + Z_CS_PIN + SPINDLE_LASER_ENA_PIN (conditional conflicts) │ +│ • GP5: Z_STEP_PIN + FILWIDTH_PIN + SPINDLE_DIR_PIN (conditional conflicts) │ +│ • GP6: CASE_LIGHT_PIN + SPINDLE_LASER_PWM_PIN (conditional - both PWM) │ +│ • GP21: FAN1_PIN + FIL_RUNOUT_PIN (may conflict if both features enabled) │ +│ • GP29: ALL assigned to same pin: │ +│ - X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_CS_PIN (4 pins) │ +│ - Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_CS_PIN (4 pins) │ +│ - E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, E0_CS_PIN (4 pins) │ +│ - LCD_PINS_EN (CR10_STOCKDISPLAY), LCD_PINS_D7, DOGLCD_CS (ELB_FULL_GRAPHIC_CONTROLLER) │ +│ → 12+ critical functions sharing ONE GPIO - PRINTER CANNOT FUNCTION! │ +└───────────────────────────────────────────────────────────────────────────────────────────────────────────────┘ +*/ + +#error "Pin assignments for this board are not for practical use. See comments in pins_RP2040.h" diff --git a/Marlin/src/sd/SdBaseFile.h b/Marlin/src/sd/SdBaseFile.h index dc31e8492d..e2dbf489f1 100644 --- a/Marlin/src/sd/SdBaseFile.h +++ b/Marlin/src/sd/SdBaseFile.h @@ -46,6 +46,19 @@ struct filepos_t { filepos_t() : position(0), cluster(0) {} }; +// Avoid conflict with RP2040 / newlib fcntl.h +#ifdef __PLAT_RP2040__ + #undef O_RDONLY + #undef O_WRONLY + #undef O_RDWR + #undef O_ACCMODE + #undef O_APPEND + #undef O_SYNC + #undef O_TRUNC + #undef O_CREAT + #undef O_EXCL +#endif + // use the gnu style oflag in open() uint8_t const O_READ = 0x01, // open() oflag for reading O_RDONLY = O_READ, // open() oflag - same as O_IN diff --git a/Marlin/src/sd/SdFatStructs.h b/Marlin/src/sd/SdFatStructs.h index b3f94b57a0..bacff4e1c0 100644 --- a/Marlin/src/sd/SdFatStructs.h +++ b/Marlin/src/sd/SdFatStructs.h @@ -32,7 +32,9 @@ #include -#define PACKED __attribute__((__packed__)) +#ifndef PACKED + #define PACKED __attribute__((__packed__)) +#endif /** * mostly from Microsoft document fatgen103.doc diff --git a/ini/raspberrypi.ini b/ini/raspberrypi.ini index 059f4d1821..2ee74631f9 100644 --- a/ini/raspberrypi.ini +++ b/ini/raspberrypi.ini @@ -16,12 +16,13 @@ build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} arduino-libraries/Servo https://github.com/pkElectronics/SoftwareSerialM#master + #adafruit/Adafruit TinyUSB Library #lvgl/lvgl@^8.1.0 lib_ignore = WiFi -build_flags = ${common.build_flags} -D__PLAT_RP2040__ -DPLATFORM_M997_SUPPORT -Wno-expansion-to-defined -Wno-vla -Wno-ignored-qualifiers +build_flags = ${common.build_flags} -D__PLAT_RP2040__ -DPLATFORM_M997_SUPPORT -DNO_SD_HOST_DRIVE -Wno-expansion-to-defined -Wno-vla -Wno-ignored-qualifiers #debug_tool = jlink #upload_protocol = jlink -custom_marlin.HAS_SD_HOST_DRIVE = tinyusb +#custom_marlin.HAS_SD_HOST_DRIVE = tinyusb [env:RP2040-alt] extends = env:RP2040