0
0
Fork 0
mirror of https://github.com/MarlinFirmware/Marlin.git synced 2025-01-22 09:42:34 +00:00

RP2040 HAL with BTT SKR Pico (#24042)

This commit is contained in:
Scott Lahteine 2024-11-03 14:15:10 -06:00 committed by GitHub
parent 98ae2ad60a
commit d876b5ee3c
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
45 changed files with 3121 additions and 22 deletions

View file

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

View file

@ -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)

View file

@ -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
Marlin/src/HAL/RP2040/HAL.h Normal file
View file

@ -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);
};

View file

@ -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__

View file

@ -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__

View file

@ -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__

View file

@ -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

View file

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

View file

@ -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__

View file

@ -0,0 +1,77 @@
/**
* 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 <Servo.h>
#if 1
#include "../../core/millis_t.h"
// Inherit and expand on the official library
class libServo {
public:
libServo();
int8_t attach(const int pin = 0); // pin == 0 uses value from previous call
int8_t attach(const int pin, const int min, const int max);
void detach() { pico_servo.detach(); }
int read() { return pico_servo.read(); }
void move(const int value);
void pause();
void resume();
static void pause_all_servos();
static void resume_all_servos();
static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
private:
Servo pico_servo;
int servo_pin = 0;
millis_t delay = 0;
bool was_attached_before_pause;
int value_before_pause;
};
#else
class libServo: public Servo {
public:
void move(const int value) {
constexpr uint16_t servo_delay[] = SERVO_DELAY;
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
if (attach(servo_info[servoIndex].Pin.nbr) >= 0) { // try to reattach
write(value);
safe_delay(servo_delay[servoIndex]); // delay to allow servo to reach position
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
};
class libServo;
typedef libServo hal_servo_t;
#endif

View file

@ -0,0 +1,33 @@
/**
* 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/>.
*
*/
#ifdef __PLAT_RP2040__
#include <iostream>
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) {
char format_string[20];
snprintf(format_string, 20, "%%%d.%df", __width, __prec);
sprintf(__s, format_string, __val);
return __s;
}
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,29 @@
/**
* 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 <stddef.h>
// #include <stdint.h>
// #include <math.h>
// #include <cstring>
char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);

View file

@ -0,0 +1,88 @@
/**
* 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 ENABLED(FLASH_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
// NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module
// Use EEPROM.h for compatibility, for now.
#include <EEPROM.h>
static bool eeprom_data_written = false;
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE size_t(E2END + 1)
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_start() {
EEPROM.begin(); // Avoid EEPROM.h warning (do nothing)
eeprom_buffer_fill();
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();
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
eeprom_data_written = false;
}
return true;
}
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);
eeprom_data_written = true;
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
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);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // FLASH_EEPROM_EMULATION
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,79 @@
/**
* 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 USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE size_t(E2END + 1)
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
uint16_t written = 0;
while (size--) {
uint8_t v = *value;
uint8_t * const p = (uint8_t * const)pos;
if (v != eeprom_read_byte(p)) { // EEPROM has only ~100,000 write cycles, so only write bytes that have changed!
eeprom_write_byte(p, v);
if (++written & 0x7F) delay(2); else safe_delay(2); // Avoid triggering watchdog during long EEPROM writes
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
// Read from either external EEPROM, program flash or Backup SRAM
const uint8_t c = eeprom_read_byte((uint8_t*)pos);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // USE_WIRED_EEPROM
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,60 @@
/**
* 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 "../../module/endstops.h"
// One ISR for all EXT-Interrupts
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(digitalPinToInterrupt(P), endstop_ISR, CHANGE)
TERN_(USE_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(USE_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(USE_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(USE_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(USE_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN_PIN, _ATTACH(Z_MIN_PIN));
TERN_(USE_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(USE_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(USE_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(USE_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(USE_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(USE_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(USE_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(USE_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(USE_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(USE_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(USE_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -0,0 +1,43 @@
/**
* 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"
#include "HAL.h"
#include "pinDefinitions.h"
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
analogWrite(pin, v);
}
void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
mbed::PwmOut* pwm = digitalPinToPwm(pin);
if (pwm != NULL) delete pwm;
pwm = new mbed::PwmOut(digitalPinToPinName(pin));
digitalPinToPwm(pin) = pwm;
pwm->period_ms(1000 / f_desired);
}
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,32 @@
/**
* 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"
void FastIO_init() {
}
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,87 @@
/**
* 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
/**
* Fast I/O interfaces for RP2040
* These use GPIO register access for fast port manipulation.
*/
// ------------------------
// Public Variables
// ------------------------
// ------------------------
// Public functions
// ------------------------
void FastIO_init(); // Must be called before using fast io macros
#define FASTIO_INIT() FastIO_init()
// ------------------------
// Defines
// ------------------------
#define _BV32(b) (1UL << (b))
#ifndef PWM
#define PWM OUTPUT
#endif
#define _WRITE(IO, V) digitalWrite((IO), (V))
#define _READ(IO) digitalRead(IO)
#define _TOGGLE(IO) digitalWrite(IO, !digitalRead(IO))
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) //!< Output Push Pull Mode & GPIO_NOPULL
#define _SET_OUTPUT_OD(IO) pinMode(IO, OUTPUT_OPEN_DRAIN)
#define WRITE(IO,V) _WRITE(IO,V)
#define READ(IO) _READ(IO)
#define TOGGLE(IO) _TOGGLE(IO)
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define OUT_WRITE_OD(IO,V) do{ _SET_OUTPUT_OD(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) //!< Input Floating Mode
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) //!< Input with Pull-up activation
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) //!< Input with Pull-down activation
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) true //digitalPinHasPWM(P)
#define NO_COMPILE_TIME_PWM
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
#undef I2C_SDA
#define I2C_SDA_PIN PIN_WIRE_SDA
#undef I2C_SCL
#define I2C_SCL_PIN PIN_WIRE_SCL

View file

@ -0,0 +1,22 @@
/**
* 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

View file

@ -0,0 +1,35 @@
/**
* 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
#if ALL(SDSUPPORT, USBD_USE_CDC_MSC) && DISABLED(NO_SD_HOST_DRIVE)
#define HAS_SD_HOST_DRIVE 1
#endif
// Fix F_CPU not being a compile-time constant in RP2040 framework
#ifdef BOARD_F_CPU
#undef F_CPU
#define F_CPU BOARD_F_CPU
#endif
// The Sensitive Pins array is not optimizable
#define RUNTIME_ONLY_ANALOG_TO_DIGITAL

View file

@ -0,0 +1,29 @@
/**
* 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
// If no real or emulated EEPROM selected, fall back to SD emulation
#if USE_FALLBACK_EEPROM
#define SDCARD_EEPROM_EMULATION
#elif ANY(I2C_EEPROM, SPI_EEPROM)
#define USE_SHARED_EEPROM 1
#endif

View file

@ -0,0 +1,22 @@
/**
* 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

View file

@ -0,0 +1,60 @@
/**
* 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
/**
* Test RP2040-specific configuration values for errors at compile-time.
*/
//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif
#if ENABLED(SDCARD_EEPROM_EMULATION) && DISABLED(SDSUPPORT)
#undef SDCARD_EEPROM_EMULATION // Avoid additional error noise
#if USE_FALLBACK_EEPROM
#warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION."
#endif
#error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation."
#endif
#if ENABLED(SRAM_EEPROM_EMULATION)
#error "SRAM_EEPROM_EMULATION is not supported for RP2040."
#endif
#if ALL(PRINTCOUNTER, FLASH_EEPROM_EMULATION)
#warning "FLASH_EEPROM_EMULATION may cause long delays when writing and should not be used while printing."
#error "Disable PRINTCOUNTER or choose another EEPROM emulation."
#endif
#if ENABLED(FLASH_EEPROM_LEVELING)
#error "FLASH_EEPROM_LEVELING is not supported for RP2040."
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
#error "SERIAL_STATS_MAX_RX_QUEUED is not supported on RP2040."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
#error "SERIAL_STATS_DROPPED_RX is not supported on RP2040."
#endif
#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI)
#error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are not supported for RP2040."
#endif

View file

@ -0,0 +1,136 @@
/**
* 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 HAS_SD_HOST_DRIVE
#include "../shared/Marduino.h"
#include "msc_sd.h"
#include "usbd_core.h"
#include "../../sd/cardreader.h"
#include <USB.h>
#include <USBMscHandler.h>
#define BLOCK_SIZE 512
#define PRODUCT_ID 0x29
class Sd2CardUSBMscHandler : public USBMscHandler {
public:
DiskIODriver* diskIODriver() {
#if ENABLED(MULTI_VOLUME)
#if SHARED_VOLUME_IS(SD_ONBOARD)
return &card.media_driver_sdcard;
#elif SHARED_VOLUME_IS(USB_FLASH_DRIVE)
return &card.media_driver_usbFlash;
#endif
#else
return card.diskIODriver();
#endif
}
bool GetCapacity(uint32_t *pBlockNum, uint16_t *pBlockSize) {
*pBlockNum = diskIODriver()->cardSize();
*pBlockSize = BLOCK_SIZE;
return true;
}
bool Write(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
auto sd2card = diskIODriver();
// single block
if (blkLen == 1) {
watchdog_refresh();
sd2card->writeBlock(blkAddr, pBuf);
return true;
}
// multi block optimization
sd2card->writeStart(blkAddr, blkLen);
while (blkLen--) {
watchdog_refresh();
sd2card->writeData(pBuf);
pBuf += BLOCK_SIZE;
}
sd2card->writeStop();
return true;
}
bool Read(uint8_t *pBuf, uint32_t blkAddr, uint16_t blkLen) {
auto sd2card = diskIODriver();
// single block
if (blkLen == 1) {
watchdog_refresh();
sd2card->readBlock(blkAddr, pBuf);
return true;
}
// multi block optimization
sd2card->readStart(blkAddr);
while (blkLen--) {
watchdog_refresh();
sd2card->readData(pBuf);
pBuf += BLOCK_SIZE;
}
sd2card->readStop();
return true;
}
bool IsReady() {
return diskIODriver()->isReady();
}
};
Sd2CardUSBMscHandler usbMscHandler;
/* USB Mass storage Standard Inquiry Data */
uint8_t Marlin_STORAGE_Inquirydata[] = { /* 36 */
/* LUN 0 */
0x00,
0x80,
0x02,
0x02,
(STANDARD_INQUIRY_DATA_LEN - 5),
0x00,
0x00,
0x00,
'M', 'A', 'R', 'L', 'I', 'N', ' ', ' ', /* Manufacturer : 8 bytes */
'P', 'r', 'o', 'd', 'u', 'c', 't', ' ', /* Product : 16 Bytes */
' ', ' ', ' ', ' ', ' ', ' ', ' ', ' ',
'0', '.', '0', '1', /* Version : 4 Bytes */
};
USBMscHandler *pSingleMscHandler = &usbMscHandler;
void MSC_SD_init() {
USBDevice.end();
delay(200);
USBDevice.registerMscHandlers(1, &pSingleMscHandler, Marlin_STORAGE_Inquirydata);
USBDevice.begin();
}
#endif // HAS_SD_HOST_DRIVE
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,24 @@
/**
* 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
void MSC_SD_init();

View file

@ -0,0 +1,146 @@
/**
* 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 <Arduino.h>
#include "HAL.h"
#ifndef NUM_DIGITAL_PINS
#error "Expected NUM_DIGITAL_PINS not found"
#endif
/**
* Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
* because the variants in this platform do not always define all the I/O port/pins
* that a CPU has.
*
* VARIABLES:
* Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
* digitalWrite commands and by M42.
* - does not contain port/pin info
* - is not in port/pin order
* - typically a variant will only assign Ard_num to port/pins that are actually used
* Index - M43 counter - only used to get Ard_num
* x - a parameter/argument used to search the pin_array to try to find a signal name
* associated with a Ard_num
* Port_pin - port number and pin number for use with CPU registers and printing reports
*
* Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
* are accessed and/or displayed.
*
* Three arrays are used.
*
* digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
* Arduino pin number order.
*
* pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
* the preprocessor. Only the signals associated with enabled options are in this table.
* It contains:
* - name of the signal
* - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
* argument to digitalPinToPinName(IO) to get the Port_pin number
* - if it is a digital or analog signal. PWMs are considered digital here.
*
* pin_xref is a structure generated by this header file. It is generated by the
* preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
* platform for this variant.
* - Ard_num
* - printable version of Port_pin
*
* Routines with an "x" as a parameter/argument are used to search the pin_array to try to
* find a signal name associated with a port/pin.
*
* NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
* signal. The Arduino pin number is listed by the M43 I command.
*/
#define NUM_ANALOG_FIRST A0
#define MODE_PIN_INPUT 0 // Input mode (reset state)
#define MODE_PIN_OUTPUT 1 // General purpose output mode
#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))
/**
* 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
// 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;
}
bool GET_PINMODE(const pin_t Ard_num) {
const uint8_t pin_mode = get_pin_mode(Ard_num);
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;
}
bool IS_ANALOG(const pin_t Ard_num) {
return digital_pin_to_analog_pin(Ard_num) != -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;
}
void print_port(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 pwm_details(const pin_t Ard_num) {
if (PWM_PIN(Ard_num)) {
}
}

View file

@ -0,0 +1,38 @@
/**
* 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 SPI Pins: SCK, MISO, MOSI, SS
*/
#ifndef SD_SCK_PIN
#define SD_SCK_PIN PIN_SPI_SCK
#endif
#ifndef SD_MISO_PIN
#define SD_MISO_PIN PIN_SPI_MISO
#endif
#ifndef SD_MOSI_PIN
#define SD_MOSI_PIN PIN_SPI_MOSI
#endif
#ifndef SD_SS_PIN
#define SD_SS_PIN PIN_SPI_SS
#endif

View file

@ -0,0 +1,126 @@
/**
* 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"
alarm_pool_t* HAL_timer_pool_0;
alarm_pool_t* HAL_timer_pool_1;
alarm_pool_t* HAL_timer_pool_2;
alarm_pool_t* HAL_timer_pool_3;
struct repeating_timer HAL_timer_0;
struct repeating_timer HAL_timer_1;
struct repeating_timer HAL_timer_2;
struct repeating_timer HAL_timer_3;
volatile bool HAL_timer_irq_en[4] = { false, false, false, false };
void HAL_timer_init() {
//reserve all the available alarm pools to use as "pseudo" hardware timers
//HAL_timer_pool_0 = alarm_pool_create(0,2);
HAL_timer_pool_1 = alarm_pool_create(1, 6);
HAL_timer_pool_0 = HAL_timer_pool_1;
HAL_timer_pool_2 = alarm_pool_create(2, 6);
HAL_timer_pool_3 = HAL_timer_pool_2;
//HAL_timer_pool_3 = alarm_pool_create(3, 6);
irq_set_priority(TIMER_IRQ_0, 0xC0);
irq_set_priority(TIMER_IRQ_1, 0x80);
irq_set_priority(TIMER_IRQ_2, 0x40);
irq_set_priority(TIMER_IRQ_3, 0x00);
//alarm_pool_init_default();
}
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
const int64_t freq = (int64_t)frequency,
us = (1000000ll / freq) * -1ll;
bool result;
switch (timer_num) {
case 0:
result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_0, us, HAL_timer_repeating_0_callback, NULL, &HAL_timer_0);
break;
case 1:
result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_1, us, HAL_timer_repeating_1_callback, NULL, &HAL_timer_1);
break;
case 2:
result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_2, us, HAL_timer_repeating_2_callback, NULL, &HAL_timer_2);
break;
case 3:
result = alarm_pool_add_repeating_timer_us(HAL_timer_pool_3, us, HAL_timer_repeating_3_callback, NULL, &HAL_timer_3);
break;
}
UNUSED(result);
}
void HAL_timer_stop(const uint8_t timer_num) {
switch (timer_num) {
case 0: cancel_repeating_timer(&HAL_timer_0); break;
case 1: cancel_repeating_timer(&HAL_timer_1); break;
case 2: cancel_repeating_timer(&HAL_timer_2); break;
case 3: cancel_repeating_timer(&HAL_timer_3); break;
}
}
int64_t HAL_timer_alarm_pool_0_callback(long int, void*) {
if (HAL_timer_irq_en[0]) HAL_timer_0_callback();
return 0;
}
int64_t HAL_timer_alarm_pool_1_callback(long int, void*) {
if (HAL_timer_irq_en[1]) HAL_timer_1_callback();
return 0;
}
int64_t HAL_timer_alarm_pool_2_callback(long int, void*) {
if (HAL_timer_irq_en[2]) HAL_timer_2_callback();
return 0;
}
int64_t HAL_timer_alarm_pool_3_callback(long int, void*) {
if (HAL_timer_irq_en[3]) HAL_timer_3_callback();
return 0;
}
bool HAL_timer_repeating_0_callback(repeating_timer* timer) {
if (HAL_timer_irq_en[0]) HAL_timer_0_callback();
return true;
}
bool HAL_timer_repeating_1_callback(repeating_timer* timer) {
if (HAL_timer_irq_en[1]) HAL_timer_1_callback();
return true;
}
bool HAL_timer_repeating_2_callback(repeating_timer* timer) {
if (HAL_timer_irq_en[2]) HAL_timer_2_callback();
return true;
}
bool HAL_timer_repeating_3_callback(repeating_timer* timer) {
if (HAL_timer_irq_en[3]) HAL_timer_3_callback();
return true;
}
void __attribute__((weak)) HAL_timer_0_callback() {}
void __attribute__((weak)) HAL_timer_1_callback() {}
void __attribute__((weak)) HAL_timer_2_callback() {}
void __attribute__((weak)) HAL_timer_3_callback() {}
#endif // __PLAT_RP2040__

View file

@ -0,0 +1,177 @@
/**
* 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 <stdint.h>
#include "../../core/macros.h"
#ifdef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
#undef PICO_TIME_DEFAULT_ALARM_POOL_DISABLED
#define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0
#else
#define PICO_TIME_DEFAULT_ALARM_POOL_DISABLED 0
#endif
// ------------------------
// Defines
// ------------------------
//#define _HAL_TIMER(T) _CAT(LPC_TIM, T)
//#define _HAL_TIMER_IRQ(T) TIMER##T##_IRQn
//#define __HAL_TIMER_ISR(T) extern "C" alarm_callback_t HAL_timer_alarm_pool_##T##_callback()
#define __HAL_TIMER_ISR(T) extern void HAL_timer_##T##_callback()
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
typedef uint64_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFF
#define HAL_TIMER_RATE (1000000ull) // fixed value as we use a microsecond timesource
#ifndef MF_TIMER_STEP
#define MF_TIMER_STEP 0 // Timer Index for Stepper
#endif
#ifndef MF_TIMER_PULSE
#define MF_TIMER_PULSE MF_TIMER_STEP
#endif
#ifndef MF_TIMER_TEMP
#define MF_TIMER_TEMP 1 // Timer Index for Temperature
#endif
#ifndef MF_TIMER_PWM
#define MF_TIMER_PWM 3 // Timer Index for PWM
#endif
#define TEMP_TIMER_RATE HAL_TIMER_RATE
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_RATE HAL_TIMER_RATE / 10 // 100khz roughly
#define STEPPER_TIMER_TICKS_PER_US (0.1) // fixed value as we use a microsecond timesource
#define STEPPER_TIMER_PRESCALE (10)
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_STEP)
#endif
#ifndef HAL_TEMP_TIMER_ISR
#define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_TEMP)
#endif
// Timer references by index
//#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP)
//#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP)
extern alarm_pool_t* HAL_timer_pool_0;
extern alarm_pool_t* HAL_timer_pool_1;
extern alarm_pool_t* HAL_timer_pool_2;
extern alarm_pool_t* HAL_timer_pool_3;
extern struct repeating_timer HAL_timer_0;
void HAL_timer_0_callback();
void HAL_timer_1_callback();
void HAL_timer_2_callback();
void HAL_timer_3_callback();
int64_t HAL_timer_alarm_pool_0_callback(long int, void*);
int64_t HAL_timer_alarm_pool_1_callback(long int, void*);
int64_t HAL_timer_alarm_pool_2_callback(long int, void*);
int64_t HAL_timer_alarm_pool_3_callback(long int, void*);
bool HAL_timer_repeating_0_callback(repeating_timer* timer);
bool HAL_timer_repeating_1_callback(repeating_timer* timer);
bool HAL_timer_repeating_2_callback(repeating_timer* timer);
bool HAL_timer_repeating_3_callback(repeating_timer* timer);
extern volatile bool HAL_timer_irq_en[4];
// ------------------------
// Public functions
// ------------------------
void HAL_timer_init();
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_stop(const uint8_t timer_num);
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t compare) {
if (timer_num == MF_TIMER_STEP){
if (compare == HAL_TIMER_TYPE_MAX){
HAL_timer_stop(timer_num);
return;
}
}
compare = compare *10; //Dirty fix, figure out a proper way
switch (timer_num) {
case 0:
alarm_pool_add_alarm_in_us(HAL_timer_pool_0 ,compare , HAL_timer_alarm_pool_0_callback ,0 ,false );
break;
case 1:
alarm_pool_add_alarm_in_us(HAL_timer_pool_1 ,compare , HAL_timer_alarm_pool_1_callback ,0 ,false );
break;
case 2:
alarm_pool_add_alarm_in_us(HAL_timer_pool_2 ,compare , HAL_timer_alarm_pool_2_callback ,0 ,false );
break;
case 3:
alarm_pool_add_alarm_in_us(HAL_timer_pool_3 ,compare , HAL_timer_alarm_pool_3_callback ,0 ,false );
break;
}
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
return 0;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
if (timer_num == MF_TIMER_STEP) return 0ull;
return time_us_64();
}
FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) {
HAL_timer_irq_en[timer_num] = 1;
}
FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
HAL_timer_irq_en[timer_num] = 0;
}
FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
return HAL_timer_irq_en[timer_num]; //lucky coincidence that timer_num and rp2040 irq num matches
}
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
return;
}
#define HAL_timer_isr_epilogue(T) NOOP

View file

@ -108,7 +108,6 @@
SPI.beginTransaction(spiConfig);
SPI.transfer(buf, nbyte);
SPI.endTransaction();
}
/**

View file

@ -54,6 +54,8 @@
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD51/NAME)
#elif defined(__SAMD21__)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/SAMD21/NAME)
#elif defined(__PLAT_RP2040__)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/RP2040/NAME)
#else
#error "Unsupported Platform!"
#endif

View file

@ -82,13 +82,15 @@
#include "../STM32/Servo.h"
#elif defined(ARDUINO_ARCH_ESP32)
#include "../ESP32/Servo.h"
#elif defined(__PLAT_RP2040__)
#include "../RP2040/Servo.h"
#else
#include <stdint.h>
#if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__)
#if defined(__AVR__) || defined(ARDUINO_ARCH_SAM) || defined(__SAMD51__) || defined(__SAMD21__) || defined(__PLAT_RP2040__)
// we're good to go
#else
#error "This library only supports boards with an AVR, SAM3X, SAMD21 or SAMD51 processor."
#error "This library only supports boards with an AVR, SAM3X, SAMD21, SAMD51, or RP2040 processor."
#endif
#define Servo_VERSION 2 // software version of this library

View file

@ -170,19 +170,19 @@
#define BOARD_GT2560_V3_A20 1319 // Geeetech GT2560 Rev B for A20(M/T/D)
#define BOARD_GT2560_V4 1320 // Geeetech GT2560 Rev B for A10(M/T/D)
#define BOARD_GT2560_V4_A20 1321 // Geeetech GT2560 Rev B for A20(M/T/D)
#define BOARD_EINSTART_S 1322 // Einstart retrofit
#define BOARD_WANHAO_ONEPLUS 1323 // Wanhao 0ne+ i3 Mini
#define BOARD_OVERLORD 1324 // Overlord/Overlord Pro
#define BOARD_HJC2560C_REV1 1325 // ADIMLab Gantry v1
#define BOARD_HJC2560C_REV2 1326 // ADIMLab Gantry v2
#define BOARD_LEAPFROG_XEED2015 1327 // Leapfrog Xeed 2015
#define BOARD_PICA_REVB 1328 // PICA Shield (original version)
#define BOARD_PICA 1329 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1330 // Intamsys 4.0 (Funmat HT)
#define BOARD_MALYAN_M180 1331 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
#define BOARD_PROTONEER_CNC_SHIELD_V3 1332 // Mega controller & Protoneer CNC Shield V3.00
#define BOARD_WEEDO_62A 1333 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
#define BOARD_GT2560_V41B 1334 // Geeetech GT2560 V4.1B for A10(M/T/D)
#define BOARD_GT2560_V41B 1322 // Geeetech GT2560 V4.1B for A10(M/T/D)
#define BOARD_EINSTART_S 1323 // Einstart retrofit
#define BOARD_WANHAO_ONEPLUS 1324 // Wanhao 0ne+ i3 Mini
#define BOARD_OVERLORD 1325 // Overlord/Overlord Pro
#define BOARD_HJC2560C_REV1 1326 // ADIMLab Gantry v1
#define BOARD_HJC2560C_REV2 1327 // ADIMLab Gantry v2
#define BOARD_LEAPFROG_XEED2015 1328 // Leapfrog Xeed 2015
#define BOARD_PICA_REVB 1329 // PICA Shield (original version)
#define BOARD_PICA 1330 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1331 // Intamsys 4.0 (Funmat HT)
#define BOARD_MALYAN_M180 1332 // Malyan M180 Mainboard Version 2 (no display function, direct G-code only)
#define BOARD_PROTONEER_CNC_SHIELD_V3 1333 // Mega controller & Protoneer CNC Shield V3.00
#define BOARD_WEEDO_62A 1334 // WEEDO 62A board (TINA2, Monoprice Cadet, etc.)
//
// ATmega1281, ATmega2561
@ -534,6 +534,13 @@
#define BOARD_AQUILA_V101 7200 // Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 as found in the Voxelab Aquila X2 and C2
#define BOARD_CREALITY_ENDER2P_V24S4 7201 // Creality Ender 2 Pro v2.4.S4_170 (HC32f460kcta)
//
// Raspberry Pi
//
#define BOARD_RP2040 6200 // Generic RP2040 Test board
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
//
// Custom board
//

View file

@ -27,6 +27,8 @@
#include "../feature/ethernet.h"
#endif
#include <stdlib.h> // dtostrf
// Echo commands to the terminal by default in dev mode
uint8_t marlin_debug_flags = TERN(MARLIN_DEV_MODE, MARLIN_DEBUG_ECHO, MARLIN_DEBUG_NONE);

View file

@ -25,6 +25,8 @@
#include "../inc/MarlinConfigPre.h"
#include "../core/utility.h"
#pragma GCC diagnostic ignored "-Wimplicit-fallthrough"
constexpr char DIGIT(const uint8_t n) { return '0' + n; }
template <typename T1, typename T2>

View file

@ -336,6 +336,8 @@
#include "mega/pins_GT2560_V4.h" // ATmega2560 env:mega2560
#elif MB(GT2560_V4_A20)
#include "mega/pins_GT2560_V4_A20.h" // ATmega2560 env:mega2560
#elif MB(GT2560_V41B)
#include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560ext
#elif MB(EINSTART_S)
#include "mega/pins_EINSTART-S.h" // ATmega2560, ATmega1280 env:mega2560ext env:mega1280
#elif MB(WANHAO_ONEPLUS)
@ -360,8 +362,6 @@
#include "mega/pins_PROTONEER_CNC_SHIELD_V3.h" // ATmega2560 env:mega2560
#elif MB(WEEDO_62A)
#include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560
#elif MB(GT2560_V41B)
#include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560ext
//
// ATmega1281, ATmega2561
@ -938,6 +938,15 @@
#elif MB(CREALITY_ENDER2P_V24S4)
#include "hc32f4/pins_CREALITY_ENDER2P_V24S4.h" // HC32F460 env:HC32F460C_e2p24s4
//
// Raspberry Pi RP2040
//
#elif MB(RP2040)
#include "rp2040/pins_RP2040.h" // RP2040 env:RP2040
#elif MB(BTT_SKR_PICO)
#include "rp2040/pins_BTT_SKR_Pico.h" // RP2040 env:SKR_Pico env:SKR_Pico_UART
//
// Custom board (with custom PIO env)
//

View file

@ -161,6 +161,11 @@
REPORT_NAME_ANALOG(__LINE__, TEMP_BOARD_PIN)
#endif
#endif
#if PIN_EXISTS(TEMP_SOC)
#if ANALOG_OK(TEMP_SOC_PIN)
REPORT_NAME_ANALOG(__LINE__, TEMP_SOC_PIN)
#endif
#endif
#if PIN_EXISTS(ADC_KEYPAD)
#if ANALOG_OK(ADC_KEYPAD_PIN)
REPORT_NAME_ANALOG(__LINE__, ADC_KEYPAD_PIN)

View file

@ -530,9 +530,13 @@
#define TEMP_BED_PIN -1
#endif
// Use ATEMP if TEMP_SOC_PIN is not defined
#if !defined(TEMP_SOC_PIN) && defined(ATEMP)
#define TEMP_SOC_PIN ATEMP
// Get TEMP_SOC_PIN from the platform, if not defined
#ifndef TEMP_SOC_PIN
#ifdef ATEMP
#define TEMP_SOC_PIN ATEMP
#elif defined(HAL_ADC_MCU_TEMP_DUMMY_PIN)
#define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN
#endif
#endif
#ifndef SD_DETECT_PIN

View file

@ -0,0 +1,26 @@
/**
* 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
#if NOT_TARGET(__PLAT_RP2040__)
#error "Oops! Make sure to build with target platform 'RP2040'."
#endif

View file

@ -0,0 +1,157 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2022 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
/**
* BigTreeTech SKR Pico
* https://github.com/bigtreetech/SKR-Pico
*/
#include "env_validate.h"
#define BOARD_INFO_NAME "BTT SKR Pico"
#define DEFAULT_MACHINE_NAME "BIQU 3D Printer"
#define USBCON
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x2000 // 8KB
#endif
//
// Servos
//
#define SERVO0_PIN 29
//
// Limit Switches
//
#define X_DIAG_PIN 4
#define Y_DIAG_PIN 3
#define Z_DIAG_PIN 25 // probe:z_virtual_endstop
#define X_STOP_PIN X_DIAG_PIN
#define Y_STOP_PIN Y_DIAG_PIN
#define Z_STOP_PIN Z_DIAG_PIN
#ifndef FIL_RUNOUT_PIN
#define FIL_RUNOUT_PIN 16 // E0-STOP
#endif
#ifndef Z_MIN_PROBE_PIN
#define Z_MIN_PROBE_PIN 22
#endif
//
// Steppers
//
#define X_STEP_PIN 11
#define X_DIR_PIN 10
#define X_ENABLE_PIN 12
#define Y_STEP_PIN 6
#define Y_DIR_PIN 5
#define Y_ENABLE_PIN 7
#define Z_STEP_PIN 19
#define Z_DIR_PIN 28
#define Z_ENABLE_PIN 2
#define E0_STEP_PIN 14
#define E0_DIR_PIN 13
#define E0_ENABLE_PIN 15
//
// Temperature Sensors
//
#define TEMP_0_PIN 27 // Analog Input
#define TEMP_BED_PIN 26 // Analog Input
//
// Heaters / Fans
//
#define HEATER_0_PIN 23
#define HEATER_BED_PIN 21
#define FAN0_PIN 17
#define FAN1_PIN 18
#if HAS_CUTTER
#define SPINDLE_LASER_ENA_PIN 0
#define SPINDLE_LASER_PWM_PIN 1
#else
#define FAN2_PIN 20
#endif
//
// Misc. Functions
//
#define NEOPIXEL_PIN 24
/**
* TMC2208/TMC2209 stepper drivers
*/
#if HAS_TMC_UART
/**
* Hardware serial communication ports.
* If undefined software serial is used according to the pins below
*/
//#define X_HARDWARE_SERIAL Serial1
//#define X2_HARDWARE_SERIAL Serial1
//#define Y_HARDWARE_SERIAL Serial1
//#define Y2_HARDWARE_SERIAL Serial1
//#define Z_HARDWARE_SERIAL MSerial1
//#define Z2_HARDWARE_SERIAL Serial1
//#define E0_HARDWARE_SERIAL Serial1
//#define E1_HARDWARE_SERIAL Serial1
//#define E2_HARDWARE_SERIAL Serial1
//#define E3_HARDWARE_SERIAL Serial1
//#define E4_HARDWARE_SERIAL Serial1
/**
* Software serial
*/
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN 8
#endif
#ifndef X_SERIAL_RX_PIN
#define X_SERIAL_RX_PIN 9
#endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN 8
#endif
#ifndef Y_SERIAL_RX_PIN
#define Y_SERIAL_RX_PIN 9
#endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN 8
#endif
#ifndef Z_SERIAL_RX_PIN
#define Z_SERIAL_RX_PIN 9
#endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN 8
#endif
#ifndef E0_SERIAL_RX_PIN
#define E0_SERIAL_RX_PIN 9
#endif
#endif

View file

@ -0,0 +1,562 @@
/**
* 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 "env_validate.h"
#define BOARD_INFO_NAME "RP2040 Test"
#define DEFAULT_MACHINE_NAME "RP2040 Test"
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
//
// Servos
//
#define SERVO0_PIN 14
//
// Limit Switches
//
#define X_STOP_PIN 13
#define Y_STOP_PIN 3
#define Z_STOP_PIN 2
//
// Steppers
//
#define X_STEP_PIN 29
#define X_DIR_PIN 29
#define X_ENABLE_PIN 29
#ifndef X_CS_PIN
#define X_CS_PIN 29
#endif
#define Y_STEP_PIN 29
#define Y_DIR_PIN 29
#define Y_ENABLE_PIN 29
#ifndef Y_CS_PIN
#define Y_CS_PIN 29
#endif
#define Z_STEP_PIN 5
#define Z_DIR_PIN 4
#define Z_ENABLE_PIN 7
#ifndef Z_CS_PIN
#define Z_CS_PIN 4
#endif
#define E0_STEP_PIN 29
#define E0_DIR_PIN 29
#define E0_ENABLE_PIN 29
#ifndef E0_CS_PIN
#define E0_CS_PIN 29
#endif
//#define E1_STEP_PIN 36
//#define E1_DIR_PIN 34
//#define E1_ENABLE_PIN 30
//#ifndef E1_CS_PIN
// #define E1_CS_PIN 44
//#endif
//
// Temperature Sensors
//
#define TEMP_0_PIN A0 // Analog Input
#define TEMP_1_PIN A1 // Analog Input
#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 DISABLED(SDSUPPORT)
#define TEMP_0_CS_PIN 17 // Don't use 53 if using Display/SD card
#else
#define TEMP_0_CS_PIN 17 // Don't use 49 (SD_DETECT_PIN)
#endif
//
// Heaters / Fans
//
#define HEATER_0_PIN 24
// Non-specific are "EFB" (i.e., "EFBF" or "EFBE")
#define FAN0_PIN 23
#define HEATER_BED_PIN 25
#if HOTENDS == 1 && DISABLED(HEATERS_PARALLEL)
#define FAN1_PIN 21
#else
#define HEATER_1_PIN MOSFET_D_PIN
#endif
#ifndef FAN0_PIN
#define FAN0_PIN 4 // IO pin. Buffer needed
#endif
//
// Misc. Functions
//
#define SDSS 20
//#define LED_PIN 13
#define NEOPIXEL_PIN 15
#ifndef FILWIDTH_PIN
#define FILWIDTH_PIN 5 // Analog Input on AUX2
#endif
// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector
#ifndef FIL_RUNOUT_PIN
#define FIL_RUNOUT_PIN 21
#endif
#ifndef PS_ON_PIN
#define PS_ON_PIN 12
#endif
#if ENABLED(CASE_LIGHT_ENABLE) && !defined(CASE_LIGHT_PIN) && !defined(SPINDLE_LASER_ENA_PIN)
#if NUM_SERVOS <= 1 // Prefer the servo connector
#define CASE_LIGHT_PIN 6 // Hardware PWM
#elif HAS_FREE_AUX2_PINS // try to use AUX 2
#define CASE_LIGHT_PIN 21 // Hardware PWM
#endif
#endif
//
// M3/M4/M5 - Spindle/Laser Control
//
#if HAS_CUTTER && !PIN_EXISTS(SPINDLE_LASER_ENA)
#if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // Prefer the servo connector
#define SPINDLE_LASER_ENA_PIN 4 // Pullup or pulldown!
#define SPINDLE_LASER_PWM_PIN 6 // Hardware PWM
#define SPINDLE_DIR_PIN 5
#elif HAS_FREE_AUX2_PINS // try to use AUX 2
#define SPINDLE_LASER_ENA_PIN 22 // Pullup or pulldown!
#define SPINDLE_LASER_PWM_PIN 23 // Hardware PWM
#define SPINDLE_DIR_PIN 24
#endif
#endif
//
// Průša i3 MK2 Multiplexer Support
//
#ifndef E_MUX0_PIN
#define E_MUX0_PIN 40 // Z_CS_PIN
#endif
#ifndef E_MUX1_PIN
#define E_MUX1_PIN 42 // E0_CS_PIN
#endif
#ifndef E_MUX2_PIN
#define E_MUX2_PIN 44 // E1_CS_PIN
#endif
/**
* Default pins for TMC software SPI
*/
#if ENABLED(TMC_USE_SW_SPI)
#ifndef TMC_SW_MOSI
#define TMC_SW_MOSI 66
#endif
#ifndef TMC_SW_MISO
#define TMC_SW_MISO 44
#endif
#ifndef TMC_SW_SCK
#define TMC_SW_SCK 64
#endif
#endif
#if HAS_TMC_UART
/**
* TMC2208/TMC2209 stepper drivers
*
* Hardware serial communication ports.
* If undefined software serial is used according to the pins below
*/
//#define X_HARDWARE_SERIAL Serial1
//#define X2_HARDWARE_SERIAL Serial1
//#define Y_HARDWARE_SERIAL Serial1
//#define Y2_HARDWARE_SERIAL Serial1
#define Z_HARDWARE_SERIAL MSerial1
//#define Z2_HARDWARE_SERIAL Serial1
//#define E0_HARDWARE_SERIAL Serial1
//#define E1_HARDWARE_SERIAL Serial1
//#define E2_HARDWARE_SERIAL Serial1
//#define E3_HARDWARE_SERIAL Serial1
//#define E4_HARDWARE_SERIAL Serial1
/**
* Software serial
*/
#ifndef X_SERIAL_TX_PIN
#define X_SERIAL_TX_PIN -1
#endif
#ifndef X2_SERIAL_TX_PIN
#define X2_SERIAL_TX_PIN -1
#endif
#ifndef Y_SERIAL_TX_PIN
#define Y_SERIAL_TX_PIN -1
#endif
#ifndef Y2_SERIAL_TX_PIN
#define Y2_SERIAL_TX_PIN -1
#endif
#ifndef Z_SERIAL_TX_PIN
#define Z_SERIAL_TX_PIN 0
#endif
#ifndef Z2_SERIAL_TX_PIN
#define Z2_SERIAL_TX_PIN -1
#endif
#ifndef E0_SERIAL_TX_PIN
#define E0_SERIAL_TX_PIN -1
#endif
#ifndef E1_SERIAL_TX_PIN
#define E1_SERIAL_TX_PIN -1
#endif
#ifndef E2_SERIAL_TX_PIN
#define E2_SERIAL_TX_PIN -1
#endif
#ifndef E3_SERIAL_TX_PIN
#define E3_SERIAL_TX_PIN -1
#endif
#ifndef E4_SERIAL_TX_PIN
#define E4_SERIAL_TX_PIN -1
#endif
#ifndef E5_SERIAL_TX_PIN
#define E5_SERIAL_TX_PIN -1
#endif
#ifndef E6_SERIAL_TX_PIN
#define E6_SERIAL_TX_PIN -1
#endif
#ifndef E7_SERIAL_TX_PIN
#define E7_SERIAL_TX_PIN -1
#endif
#endif
//////////////////////////
// LCDs and Controllers //
//////////////////////////
#if ANY(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI)
#define TFT_A0_PIN 43
#define TFT_CS_PIN 49
#define TFT_DC_PIN 43
#define TFT_SCK_PIN SD_SCK_PIN
#define TFT_MOSI_PIN SD_MOSI_PIN
#define TFT_MISO_PIN SD_MISO_PIN
#define LCD_USE_DMA_SPI
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59
#define BEEPER_PIN 22
#define TOUCH_CS_PIN 33
#define SD_DETECT_PIN 41
#define HAS_SPI_FLASH 1
#if HAS_SPI_FLASH
#define SPI_DEVICE 1
#define SPI_FLASH_SIZE 0x1000000 // 16MB
#define SPI_FLASH_CS_PIN 31
#define SPI_FLASH_MOSI_PIN SD_MOSI_PIN
#define SPI_FLASH_MISO_PIN SD_MISO_PIN
#define SPI_FLASH_SCK_PIN SD_SCK_PIN
#endif
#define TFT_BUFFER_SIZE 0xFFFF
#ifndef TFT_DRIVER
#define TFT_DRIVER ST7796
#endif
#ifndef XPT2046_X_CALIBRATION
#define XPT2046_X_CALIBRATION 63934
#endif
#ifndef XPT2046_Y_CALIBRATION0
#define XPT2046_Y_CALIBRATION 63598
#endif
#ifndef XPT2046_X_OFFSET
#define XPT2046_X_OFFSET -1
#endif
#ifndef XPT2046_Y_OFFSET
#define XPT2046_Y_OFFSET -20
#endif
#define BTN_BACK 70
#elif HAS_WIRED_LCD
//
// LCD Display output pins
//
#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define LCD_PINS_RS 49 // CS chip select /SS chip slave select
#define LCD_PINS_ENABLE 51 // SID (MOSI)
#define LCD_PINS_D4 52 // SCK (CLK) clock
#elif ALL(IS_NEWPANEL, PANEL_ONE)
#define LCD_PINS_RS 40
#define LCD_PINS_ENABLE 42
#define LCD_PINS_D4 65
#define LCD_PINS_D5 66
#define LCD_PINS_D6 44
#define LCD_PINS_D7 64
#else
#if ENABLED(CR10_STOCKDISPLAY)
#define LCD_PINS_RS 27
#define LCD_PINS_ENABLE 29
#define LCD_PINS_D4 25
#if !IS_NEWPANEL
#define BEEPER_PIN 37
#endif
#elif ENABLED(ZONESTAR_LCD)
#define LCD_PINS_RS 64
#define LCD_PINS_ENABLE 44
#define LCD_PINS_D4 63
#define LCD_PINS_D5 40
#define LCD_PINS_D6 42
#define LCD_PINS_D7 65
#else
#if ANY(MKS_12864OLED, MKS_12864OLED_SSD1306)
#define LCD_PINS_DC 25 // Set as output on init
#define LCD_PINS_RS 27 // Pull low for 1s to init
// DOGM SPI LCD Support
#define DOGLCD_CS 16
#define DOGLCD_MOSI 17
#define DOGLCD_SCK 23
#define DOGLCD_A0 LCD_PINS_DC
#else
#define LCD_PINS_RS 16
#define LCD_PINS_ENABLE 17
#define LCD_PINS_D4 23
#define LCD_PINS_D5 25
#define LCD_PINS_D6 27
#endif
#define LCD_PINS_D7 29
#if !IS_NEWPANEL
#define BEEPER_PIN 33
#endif
#endif
#if !IS_NEWPANEL
// Buttons attached to a shift register
// Not wired yet
//#define SHIFT_CLK_PIN 38
//#define SHIFT_LD_PIN 42
//#define SHIFT_OUT_PIN 40
//#define SHIFT_EN_PIN 17
#endif
#endif
//
// LCD Display input pins
//
#if IS_NEWPANEL
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
#define BEEPER_PIN 37
#if ENABLED(CR10_STOCKDISPLAY)
#define BTN_EN1 17
#define BTN_EN2 23
#else
#define BTN_EN1 31
#define BTN_EN2 33
#endif
#define BTN_ENC 35
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#if ENABLED(BQ_LCD_SMART_CONTROLLER)
#define LCD_BACKLIGHT_PIN 39
#endif
#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define BTN_EN1 64
#define BTN_EN2 59
#define BTN_ENC 63
#define SD_DETECT_PIN 42
#elif ENABLED(LCD_I2C_PANELOLU2)
#define BTN_EN1 47
#define BTN_EN2 43
#define BTN_ENC 32
#define LCD_SDSS SDSS
#define KILL_PIN 41
#elif ENABLED(LCD_I2C_VIKI)
#define BTN_EN1 22 // https://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42.
#define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13.
#define BTN_ENC -1
#define LCD_SDSS SDSS
#define SD_DETECT_PIN 49
#elif ANY(VIKI2, miniVIKI)
#define DOGLCD_CS 45
#define DOGLCD_A0 44
#define LCD_SCREEN_ROT_180
#define BEEPER_PIN 33
#define STAT_LED_RED_PIN 32
#define STAT_LED_BLUE_PIN 35
#define BTN_EN1 22
#define BTN_EN2 7
#define BTN_ENC 39
#define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board
#define KILL_PIN 31
#elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define DOGLCD_CS 29
#define DOGLCD_A0 27
#define BEEPER_PIN 23
#define LCD_BACKLIGHT_PIN 33
#define BTN_EN1 35
#define BTN_EN2 37
#define BTN_ENC 31
#define LCD_SDSS SDSS
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#elif ENABLED(MKS_MINI_12864)
#define DOGLCD_A0 27
#define DOGLCD_CS 25
// GLCD features
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
#define BEEPER_PIN 37
// not connected to a pin
#define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
#define BTN_EN1 31
#define BTN_EN2 33
#define BTN_ENC 35
#define SD_DETECT_PIN 49
#define KILL_PIN 64
#elif ENABLED(MINIPANEL)
#define BEEPER_PIN 42
// not connected to a pin
#define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65
#define DOGLCD_A0 44
#define DOGLCD_CS 66
// GLCD features
// Uncomment screen orientation
//#define LCD_SCREEN_ROT_90
//#define LCD_SCREEN_ROT_180
//#define LCD_SCREEN_ROT_270
#define BTN_EN1 40
#define BTN_EN2 63
#define BTN_ENC 59
#define SD_DETECT_PIN 49
#define KILL_PIN 64
#elif ENABLED(ZONESTAR_LCD)
#define ADC_KEYPAD_PIN 12
#elif ENABLED(AZSMZ_12864)
// Pins only defined for RAMPS_SMART currently
#else
// Beeper on AUX-4
#define BEEPER_PIN 33
// Buttons are directly attached to AUX-2
#if IS_RRW_KEYPAD
#define SHIFT_OUT_PIN 40
#define SHIFT_CLK_PIN 44
#define SHIFT_LD_PIN 42
#define BTN_EN1 64
#define BTN_EN2 59
#define BTN_ENC 63
#elif ENABLED(PANEL_ONE)
#define BTN_EN1 59 // AUX2 PIN 3
#define BTN_EN2 63 // AUX2 PIN 4
#define BTN_ENC 49 // AUX3 PIN 7
#else
#define BTN_EN1 37
#define BTN_EN2 35
#define BTN_ENC 31
#define SD_DETECT_PIN 41
#endif
#if ENABLED(G3D_PANEL)
#define SD_DETECT_PIN 49
#define KILL_PIN 41
#endif
#endif
// CUSTOM SIMULATOR INPUTS
#define BTN_BACK 70
#endif // IS_NEWPANEL
#endif // HAS_WIRED_LCD

18
buildroot/tests/SKR_Pico Executable file
View file

@ -0,0 +1,18 @@
#!/usr/bin/env bash
#
# Build tests for BTT SKR Pico
#
# exit on first failure
set -e
#
# Build with the default configurations
#
restore_configs
opt_set MOTHERBOARD BOARD_BTT_SKR_PICO NUM_SERVOS 1
opt_enable Z_PROBE_SERVO_NR Z_SERVO_ANGLES Z_SAFE_HOMING M114_DETAIL
exec_test $1 $2 "Default Configuration" "$3"
# clean up
restore_configs

37
ini/raspberrypi.ini Normal file
View file

@ -0,0 +1,37 @@
#
# Marlin Firmware
# PlatformIO Configuration File
#
# See https://arduino-pico.readthedocs.io/en/latest/platformio.html
#
[env:RP2040]
platform = raspberrypi
board = pico
framework = arduino
#board_build.core = earlephilhower
#lib_ldf_mode = off
#lib_compat_mode = strict
build_src_filter = ${common.default_src_filter} +<src/HAL/RP2040>
lib_deps = ${common.lib_deps}
arduino-libraries/Servo
https://github.com/pkElectronics/SoftwareSerialM#master
#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
#debug_tool = jlink
#upload_protocol = jlink
[env:RP2040-alt]
extends = env:RP2040
platform = https://github.com/maxgerhardt/platform-raspberrypi.git
board_build.core = earlephilhower
#
# BigTreeTech SKR Pico 1.x
#
[env:SKR_Pico]
extends = env:RP2040
[env:SKR_Pico_UART]
extends = env:SKR_Pico

View file

@ -36,6 +36,7 @@ extra_configs =
ini/stm32g0.ini
ini/teensy.ini
ini/renamed.ini
ini/raspberrypi.ini
#
# The 'common' section applies to most Marlin builds.