mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2024-11-22 18:25:18 +00:00
Merge branch 'bugfix-2.1.x' of https://github.com/MarlinFirmware/Marlin into bugfix-2.1.x-Feb
This commit is contained in:
commit
00d2427792
21
.aiderignore
Normal file
21
.aiderignore
Normal file
@ -0,0 +1,21 @@
|
||||
# Build artifacts
|
||||
buildroot/
|
||||
*.o
|
||||
*.a
|
||||
*.so
|
||||
*.dylib
|
||||
*.dll
|
||||
*.exe
|
||||
|
||||
# Web assets
|
||||
*.min.js
|
||||
*.min.css
|
||||
|
||||
# Generated files
|
||||
__pycache__/
|
||||
*.pyc
|
||||
.DS_Store
|
||||
|
||||
# IDE files
|
||||
.vscode/
|
||||
.idea/
|
3
.github/workflows/ci-build-tests.yml
vendored
3
.github/workflows/ci-build-tests.yml
vendored
@ -41,6 +41,9 @@ jobs:
|
||||
matrix:
|
||||
test-platform:
|
||||
|
||||
# RP2040
|
||||
- SKR_Pico
|
||||
|
||||
# Native
|
||||
- linux_native
|
||||
- simulator_linux_release
|
||||
|
3
.gitignore
vendored
3
.gitignore
vendored
@ -169,3 +169,6 @@ __pycache__
|
||||
tags
|
||||
*.logs
|
||||
*.bak
|
||||
.aider*
|
||||
!.aiderignore
|
||||
.env
|
||||
|
@ -71,6 +71,8 @@
|
||||
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||
#endif
|
||||
|
||||
// @section serial
|
||||
|
||||
/**
|
||||
* Select the serial port on the board to use for communication with the host.
|
||||
* This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||
@ -941,7 +943,7 @@
|
||||
//============================= Mechanical Settings =========================
|
||||
//===========================================================================
|
||||
|
||||
// @section machine
|
||||
// @section kinematics
|
||||
|
||||
// Enable one of the options below for CoreXY, CoreXZ, or CoreYZ kinematics,
|
||||
// either in the usual order or reversed
|
||||
@ -965,6 +967,15 @@
|
||||
// Enable for a belt style printer with endless "Z" motion
|
||||
//#define BELTPRINTER
|
||||
|
||||
// Articulated robot (arm). Joints are directly mapped to axes with no kinematics.
|
||||
//#define ARTICULATED_ROBOT_ARM
|
||||
|
||||
// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire
|
||||
// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics).
|
||||
//#define FOAMCUTTER_XYUV
|
||||
|
||||
// @section polargraph
|
||||
|
||||
// Enable for Polargraph Kinematics
|
||||
//#define POLARGRAPH
|
||||
#if ENABLED(POLARGRAPH)
|
||||
@ -1151,15 +1162,6 @@
|
||||
#define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly
|
||||
#endif
|
||||
|
||||
// @section machine
|
||||
|
||||
// Articulated robot (arm). Joints are directly mapped to axes with no kinematics.
|
||||
//#define ARTICULATED_ROBOT_ARM
|
||||
|
||||
// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire
|
||||
// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics).
|
||||
//#define FOAMCUTTER_XYUV
|
||||
|
||||
//===========================================================================
|
||||
//============================== Endstop Settings ===========================
|
||||
//===========================================================================
|
||||
@ -1769,17 +1771,17 @@
|
||||
// @section stepper drivers
|
||||
|
||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||
// :{ 0:'Low', 1:'High' }
|
||||
#define X_ENABLE_ON 0
|
||||
#define Y_ENABLE_ON 0
|
||||
#define Z_ENABLE_ON 0
|
||||
#define E_ENABLE_ON 0 // For all extruders
|
||||
//#define I_ENABLE_ON 0
|
||||
//#define J_ENABLE_ON 0
|
||||
//#define K_ENABLE_ON 0
|
||||
//#define U_ENABLE_ON 0
|
||||
//#define V_ENABLE_ON 0
|
||||
//#define W_ENABLE_ON 0
|
||||
// :['LOW', 'HIGH']
|
||||
#define X_ENABLE_ON LOW
|
||||
#define Y_ENABLE_ON LOW
|
||||
#define Z_ENABLE_ON LOW
|
||||
#define E_ENABLE_ON LOW // For all extruders
|
||||
//#define I_ENABLE_ON LOW
|
||||
//#define J_ENABLE_ON LOW
|
||||
//#define K_ENABLE_ON LOW
|
||||
//#define U_ENABLE_ON LOW
|
||||
//#define V_ENABLE_ON LOW
|
||||
//#define W_ENABLE_ON LOW
|
||||
|
||||
// Disable axis steppers immediately when they're not being stepped.
|
||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||
@ -3459,6 +3461,8 @@
|
||||
* TFT_ROTATE_180, TFT_ROTATE_180_MIRROR_X, TFT_ROTATE_180_MIRROR_Y,
|
||||
* TFT_ROTATE_270, TFT_ROTATE_270_MIRROR_X, TFT_ROTATE_270_MIRROR_Y,
|
||||
* TFT_MIRROR_X, TFT_MIRROR_Y, TFT_NO_ROTATION
|
||||
*
|
||||
* :{ 'TFT_NO_ROTATION':'None', 'TFT_ROTATE_90':'90°', 'TFT_ROTATE_90_MIRROR_X':'90° (Mirror X)', 'TFT_ROTATE_90_MIRROR_Y':'90° (Mirror Y)', 'TFT_ROTATE_180':'180°', 'TFT_ROTATE_180_MIRROR_X':'180° (Mirror X)', 'TFT_ROTATE_180_MIRROR_Y':'180° (Mirror Y)', 'TFT_ROTATE_270':'270°', 'TFT_ROTATE_270_MIRROR_X':'270° (Mirror X)', 'TFT_ROTATE_270_MIRROR_Y':'270° (Mirror Y)', 'TFT_MIRROR_X':'Mirror X', 'TFT_MIRROR_Y':'Mirror Y' }
|
||||
*/
|
||||
//#define TFT_ROTATION TFT_NO_ROTATION
|
||||
|
||||
|
@ -1260,8 +1260,8 @@
|
||||
#define DISABLE_IDLE_E // Shut down all idle extruders
|
||||
|
||||
// Default Minimum Feedrates for printing and travel moves
|
||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum feedrate. Set with M205 S.
|
||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s. °/s for rotational-only moves) Minimum travel feedrate. Set with M205 T.
|
||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S.
|
||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T.
|
||||
|
||||
// Minimum time that a segment needs to take as the buffer gets emptied
|
||||
#define DEFAULT_MINSEGMENTTIME 20000 // (µs) Set with M205 B.
|
||||
|
@ -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)
|
||||
|
@ -41,7 +41,7 @@
|
||||
* here we define this default string as the date where the latest release
|
||||
* version was tagged.
|
||||
*/
|
||||
//#define STRING_DISTRIBUTION_DATE "2024-10-21"
|
||||
//#define STRING_DISTRIBUTION_DATE "2024-11-21"
|
||||
|
||||
/**
|
||||
* The protocol for communication to the host. Protocol indicates communication
|
||||
|
@ -22,7 +22,23 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* PWM print routines for Atmel 8 bit AVR CPUs
|
||||
* Pins Debugging for Atmel 8 bit AVR CPUs
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
@ -39,30 +55,30 @@
|
||||
#include "pinsDebug_Teensyduino.h"
|
||||
// Can't use the "digitalPinToPort" function from the Teensyduino type IDEs
|
||||
// portModeRegister takes a different argument
|
||||
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
|
||||
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
|
||||
#define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
|
||||
#define getValidPinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin))
|
||||
#define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P)
|
||||
#define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P)
|
||||
#define digitalPinToPort_DEBUG(P) digitalPinToPort(P)
|
||||
#define getValidPinMode(P) (*portModeRegister(P) & digitalPinToBitMask_DEBUG(P))
|
||||
|
||||
#elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70
|
||||
|
||||
#include "pinsDebug_plus_70.h"
|
||||
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer_plus_70(p)
|
||||
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask_plus_70(p)
|
||||
#define digitalPinToPort_DEBUG(p) digitalPinToPort_plus_70(p)
|
||||
#define digitalPinToTimer_DEBUG(P) digitalPinToTimer_plus_70(P)
|
||||
#define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask_plus_70(P)
|
||||
#define digitalPinToPort_DEBUG(P) digitalPinToPort_plus_70(P)
|
||||
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
|
||||
|
||||
#else
|
||||
|
||||
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
|
||||
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
|
||||
#define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
|
||||
#define digitalPinToTimer_DEBUG(P) digitalPinToTimer(P)
|
||||
#define digitalPinToBitMask_DEBUG(P) digitalPinToBitMask(P)
|
||||
#define digitalPinToPort_DEBUG(P) digitalPinToPort(P)
|
||||
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
|
||||
#define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)
|
||||
#define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin)
|
||||
|
||||
#endif
|
||||
|
||||
#define isValidPin(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0)
|
||||
#define isValidPin(P) (P >= 0 && P < NUMBER_PINS_TOTAL)
|
||||
#if AVR_ATmega1284_FAMILY
|
||||
#define isAnalogPin(P) WITHIN(P, analogInputToDigitalPin(7), analogInputToDigitalPin(0))
|
||||
#define digitalPinToAnalogIndex(P) int(isAnalogPin(P) ? (P) - analogInputToDigitalPin(7) : -1)
|
||||
@ -72,11 +88,11 @@
|
||||
#define isAnalogPin(P) (_ANALOG1(P) || _ANALOG2(P))
|
||||
#define digitalPinToAnalogIndex(P) int(_ANALOG1(P) ? (P) - analogInputToDigitalPin(0) : _ANALOG2(P) ? (P) - analogInputToDigitalPin(8) + 8 : -1)
|
||||
#endif
|
||||
#define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)
|
||||
#define getPinByIndex(x) pgm_read_byte(&pin_array[x].pin)
|
||||
#define MULTI_NAME_PAD 26 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
void printPinNameByIndex(uint8_t x) {
|
||||
PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name);
|
||||
void printPinNameByIndex(const uint8_t index) {
|
||||
PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[index].name);
|
||||
for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) {
|
||||
char temp_char = pgm_read_byte(name_mem_pointer + y);
|
||||
if (temp_char != 0)
|
||||
@ -109,7 +125,7 @@ void printPinNameByIndex(uint8_t x) {
|
||||
* Print a pin's PWM status.
|
||||
* Return true if it's currently a PWM pin.
|
||||
*/
|
||||
bool pwm_status(uint8_t pin) {
|
||||
bool pwm_status(const uint8_t pin) {
|
||||
char buffer[20]; // for the sprintf statements
|
||||
|
||||
switch (digitalPinToTimer_DEBUG(pin)) {
|
||||
@ -276,7 +292,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
|
||||
if (TEST(*TMSK, TOIE)) err_prob_interrupt();
|
||||
}
|
||||
|
||||
void printPinPWM(uint8_t pin) {
|
||||
void printPinPWM(const uint8_t pin) {
|
||||
switch (digitalPinToTimer_DEBUG(pin)) {
|
||||
|
||||
#if ABTEST(0)
|
||||
@ -386,7 +402,7 @@ void printPinPort(const pin_t pin) { // print port number
|
||||
#endif
|
||||
}
|
||||
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
#undef ABTEST
|
||||
|
@ -102,7 +102,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = {
|
||||
|
||||
// digitalPinToBitMask(pin) is OK
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // Teensyduino's version of digitalRead doesn't
|
||||
#define digitalRead_mod(P) extDigitalRead(P) // Teensyduino's version of digitalRead doesn't
|
||||
// disable the PWMs so we can use it as is
|
||||
|
||||
// portModeRegister(pin) is OK
|
||||
|
@ -291,7 +291,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
|
||||
uint32_t *p1 = (uint32_t*)addrflash;
|
||||
uint32_t *p2 = (uint32_t*)data;
|
||||
int count = 0;
|
||||
for (i =0; i<PageSize >> 2; i++) {
|
||||
for (i = 0; i < PageSize >> 2; i++) {
|
||||
if (p1[i] != p2[i]) {
|
||||
uint32_t delta = p1[i] ^ p2[i];
|
||||
while (delta) {
|
||||
|
@ -19,13 +19,26 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Support routines for Due
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
* Pins Debugging for DUE
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#include "../shared/Marduino.h"
|
||||
@ -63,20 +76,20 @@
|
||||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
|
||||
#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define digitalPinToAnalogIndex(p) int(p - analogInputToDigitalPin(0))
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
|
||||
#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
|
||||
#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \
|
||||
((g_APinDescription[pin].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
|
||||
#define pwm_status(P) (((g_pinStatus[P] & 0xF) == PIN_STATUS_PWM) && \
|
||||
((g_APinDescription[P].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
|
||||
#define MULTI_NAME_PAD 14 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
bool getValidPinMode(int8_t pin) { // 1: output, 0: input
|
||||
bool getValidPinMode(const pin_t pin) { // 1: output, 0: input
|
||||
volatile Pio* port = g_APinDescription[pin].pPort;
|
||||
uint32_t mask = g_APinDescription[pin].ulPin;
|
||||
uint8_t pin_status = g_pinStatus[pin] & 0xF;
|
||||
@ -85,7 +98,7 @@ bool getValidPinMode(int8_t pin) { // 1: output, 0: input
|
||||
|| pwm_status(pin));
|
||||
}
|
||||
|
||||
void printPinPWM(int32_t pin) {
|
||||
void printPinPWM(const int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
uint32_t chan = g_APinDescription[pin].ulPWMChannel;
|
||||
SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
|
||||
|
@ -37,6 +37,10 @@
|
||||
// Set pin as output
|
||||
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT)
|
||||
|
||||
// TODO: Store set modes in an array and use those to get the mode
|
||||
#define _IS_OUTPUT(IO) true
|
||||
#define _IS_INPUT(IO) true
|
||||
|
||||
// Set pin as input with pullup mode
|
||||
#define _PULLUP(IO, v) pinMode(IO, v ? INPUT_PULLUP : INPUT)
|
||||
|
||||
@ -70,6 +74,9 @@
|
||||
// Set pin as output and init
|
||||
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
|
||||
|
||||
#define IS_OUTPUT(IO) _IS_OUTPUT(IO)
|
||||
#define IS_INPUT(IO) _IS_INPUT(IO)
|
||||
|
||||
// digitalRead/Write wrappers
|
||||
#define extDigitalRead(IO) digitalRead(IO)
|
||||
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
|
||||
|
@ -22,11 +22,15 @@
|
||||
|
||||
#ifdef ARDUINO_ARCH_ESP32
|
||||
|
||||
#include <WiFi.h>
|
||||
|
||||
#undef ENABLED
|
||||
#undef DISABLED
|
||||
|
||||
#include "../../inc/MarlinConfigPre.h"
|
||||
|
||||
#if ALL(WIFISUPPORT, OTASUPPORT)
|
||||
|
||||
#include <WiFi.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include <WiFiUdp.h>
|
||||
#include <ArduinoOTA.h>
|
||||
|
71
Marlin/src/HAL/ESP32/pinsDebug.h
Normal file
71
Marlin/src/HAL/ESP32/pinsDebug.h
Normal file
@ -0,0 +1,71 @@
|
||||
/**
|
||||
* 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
|
||||
|
||||
#error "PINS_DEBUGGING is not yet supported for ESP32!"
|
||||
|
||||
/**
|
||||
* Pins Debugging for ESP32
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
|
||||
#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
|
||||
bool pwm_status(const pin_t) { return false; }
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
||||
static bool getValidPinMode(const pin_t pin) {
|
||||
return isValidPin(pin) && !IS_INPUT(pin);
|
||||
}
|
||||
|
||||
void printPinPWM(const int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
|
||||
//SERIAL_ECHOPGM("PWM = ", duty);
|
||||
}
|
||||
}
|
@ -18,41 +18,47 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Pins Debugging for HC32
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "fastio.h"
|
||||
#include <drivers/timera/timera_pwm.h>
|
||||
|
||||
//
|
||||
// Translation of routines & variables used by pinsDebug.h
|
||||
//
|
||||
#ifndef BOARD_NR_GPIO_PINS
|
||||
#error "Expected BOARD_NR_GPIO_PINS not found."
|
||||
#endif
|
||||
|
||||
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
|
||||
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
|
||||
#define isValidPin(pin) IS_GPIO_PIN(pin)
|
||||
#define isValidPin(P) IS_GPIO_PIN(P)
|
||||
|
||||
// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included
|
||||
// after it, it is available in this file as well.
|
||||
#define getPinByIndex(p) pin_t(pin_array[p].pin)
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define printPinNumber(p) \
|
||||
do { \
|
||||
sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); \
|
||||
SERIAL_ECHO(buffer); \
|
||||
} while (0)
|
||||
#define printPinAnalog(p) \
|
||||
do { \
|
||||
sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); \
|
||||
SERIAL_ECHO(buffer); \
|
||||
} while (0)
|
||||
#define PRINT_PORT(p) printPinPort(p)
|
||||
#define printPinNameByIndex(x) \
|
||||
do { \
|
||||
sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); \
|
||||
SERIAL_ECHO(buffer); \
|
||||
} while (0)
|
||||
#define getPinByIndex(x) pin_t(pin_array[x].pin)
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
#define MULTI_NAME_PAD 21 // Space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
@ -71,13 +77,13 @@
|
||||
#define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q))
|
||||
#endif
|
||||
|
||||
static int8_t digitalPinToAnalogIndex(pin_t pin) {
|
||||
int8_t digitalPinToAnalogIndex(const pin_t pin) {
|
||||
if (!isValidPin(pin)) return -1;
|
||||
const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel);
|
||||
return pin_t(adc_channel);
|
||||
}
|
||||
|
||||
static bool isAnalogPin(pin_t pin) {
|
||||
bool isAnalogPin(pin_t pin) {
|
||||
if (!isValidPin(pin)) return false;
|
||||
|
||||
if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID)
|
||||
@ -86,12 +92,12 @@ static bool isAnalogPin(pin_t pin) {
|
||||
return false;
|
||||
}
|
||||
|
||||
static bool getValidPinMode(const pin_t pin) {
|
||||
bool getValidPinMode(const pin_t pin) {
|
||||
return isValidPin(pin) && !IS_INPUT(pin);
|
||||
}
|
||||
|
||||
static bool getPinIsDigitalByIndex(const int16_t array_pin) {
|
||||
const pin_t pin = getPinByIndex(array_pin);
|
||||
bool getPinIsDigitalByIndex(const int16_t index) {
|
||||
const pin_t pin = getPinByIndex(index);
|
||||
return (!isAnalogPin(pin));
|
||||
}
|
||||
|
||||
|
@ -37,29 +37,29 @@ constexpr uint8_t NUM_ANALOG_INPUTS = 16;
|
||||
constexpr uint8_t analog_offset = NUM_DIGITAL_PINS - NUM_ANALOG_INPUTS;
|
||||
|
||||
// Get the digital pin for an analog index
|
||||
constexpr pin_t analogInputToDigitalPin(const int8_t p) {
|
||||
return (WITHIN(p, 0, NUM_ANALOG_INPUTS) ? analog_offset + p : P_NC);
|
||||
constexpr pin_t analogInputToDigitalPin(const int8_t a) {
|
||||
return (WITHIN(a, 0, NUM_ANALOG_INPUTS - 1) ? analog_offset + a : P_NC);
|
||||
}
|
||||
|
||||
// Get the analog index for a digital pin
|
||||
constexpr int8_t digitalPinToAnalogIndex(const pin_t p) {
|
||||
return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
|
||||
constexpr int8_t digitalPinToAnalogIndex(const pin_t pin) {
|
||||
return (WITHIN(pin, analog_offset, NUM_DIGITAL_PINS - 1) ? pin - analog_offset : P_NC);
|
||||
}
|
||||
|
||||
// Return the index of a pin number
|
||||
constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; }
|
||||
|
||||
// Test whether the pin is valid
|
||||
constexpr bool isValidPin(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); }
|
||||
constexpr bool isValidPin(const pin_t pin) { return WITHIN(pin, 0, NUM_DIGITAL_PINS - 1); }
|
||||
|
||||
// Test whether the pin is PWM
|
||||
constexpr bool PWM_PIN(const pin_t p) { return false; }
|
||||
constexpr bool PWM_PIN(const pin_t) { return false; }
|
||||
|
||||
// Test whether the pin is interruptible
|
||||
constexpr bool INTERRUPT_PIN(const pin_t p) { return false; }
|
||||
constexpr bool INTERRUPT_PIN(const pin_t) { return false; }
|
||||
|
||||
// Get the pin number at the given index
|
||||
constexpr pin_t GET_PIN_MAP_PIN(const int16_t ind) { return ind; }
|
||||
constexpr pin_t GET_PIN_MAP_PIN(const int16_t index) { return pin_t(index); }
|
||||
|
||||
// Parse a G-code word into a pin index
|
||||
int16_t PARSED_PIN_INDEX(const char code, const int16_t dval);
|
||||
|
@ -19,26 +19,46 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Support routines for X86_64
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
* Pins Debugging for Linux Native
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
|
||||
#define digitalRead_mod(p) digitalRead(p)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
// active ADC function/mode/code values for PINSEL registers
|
||||
constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; }
|
||||
constexpr int8_t ADC_pin_mode(const pin_t) { return -1; }
|
||||
|
||||
// The pin and index are the same on this platform
|
||||
bool getPinIsDigitalByIndex(const pin_t pin) {
|
||||
return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
|
||||
}
|
||||
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
|
||||
|
||||
#define digitalRead_mod(P) digitalRead(P)
|
||||
|
||||
int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; }
|
||||
|
||||
@ -50,11 +70,11 @@ bool getValidPinMode(const pin_t pin) {
|
||||
return (Gpio::getMode(pin) != 0); // Input/output state
|
||||
}
|
||||
|
||||
bool getPinIsDigitalByIndex(const pin_t pin) {
|
||||
return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
|
||||
}
|
||||
|
||||
void printPinPWM(const pin_t pin) {}
|
||||
void printPinPWM(const pin_t) {}
|
||||
bool pwm_status(const pin_t) { return false; }
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
|
@ -19,22 +19,35 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Support routines for LPC1768
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
* Pins Debugging for LPC1768/9
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(P), LPC176x::pin_bit(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 17 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
|
@ -25,7 +25,7 @@
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "pinsDebug.h"
|
||||
|
||||
int8_t ADC_pin_mode(pin_t pin) { return -1; }
|
||||
int8_t ADC_pin_mode(const pin_t) { return -1; }
|
||||
|
||||
int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; }
|
||||
|
||||
@ -37,6 +37,7 @@ bool getValidPinMode(const pin_t pin) {
|
||||
return (Gpio::getMode(pin) != 0); // Input/output state
|
||||
}
|
||||
|
||||
// The pin and index are the same on this platform
|
||||
bool getPinIsDigitalByIndex(const pin_t pin) {
|
||||
return !isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin);
|
||||
}
|
||||
|
@ -19,30 +19,43 @@
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* Support routines for X86_64
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
* Pins Debugging for x86_64
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
|
||||
#define digitalRead_mod(p) digitalRead(p)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0)
|
||||
#define digitalRead_mod(P) digitalRead(P)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// Active ADC function/mode/code values for PINSEL registers
|
||||
int8_t ADC_pin_mode(pin_t pin);
|
||||
int8_t get_pin_mode(const pin_t pin);
|
||||
bool getValidPinMode(const pin_t pin);
|
||||
bool getPinIsDigitalByIndex(const pin_t pin);
|
||||
int8_t ADC_pin_mode(const pin_t);
|
||||
int8_t get_pin_mode(const pin_t);
|
||||
bool getValidPinMode(const pin_t);
|
||||
bool getPinIsDigitalByIndex(const pin_t);
|
||||
void printPinPort(const pin_t);
|
||||
void printPinPWM(const pin_t);
|
||||
bool pwm_status(const pin_t);
|
||||
|
188
Marlin/src/HAL/RP2040/HAL.cpp
Normal file
188
Marlin/src/HAL/RP2040/HAL.cpp
Normal 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
250
Marlin/src/HAL/RP2040/HAL.h
Normal 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);
|
||||
};
|
69
Marlin/src/HAL/RP2040/HAL_MinSerial.cpp
Normal file
69
Marlin/src/HAL/RP2040/HAL_MinSerial.cpp
Normal 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__
|
228
Marlin/src/HAL/RP2040/HAL_SPI.cpp
Normal file
228
Marlin/src/HAL/RP2040/HAL_SPI.cpp
Normal 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__
|
39
Marlin/src/HAL/RP2040/MarlinSerial.cpp
Normal file
39
Marlin/src/HAL/RP2040/MarlinSerial.cpp
Normal 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__
|
52
Marlin/src/HAL/RP2040/MarlinSerial.h
Normal file
52
Marlin/src/HAL/RP2040/MarlinSerial.h
Normal 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
|
||||
|
1
Marlin/src/HAL/RP2040/README.md
Normal file
1
Marlin/src/HAL/RP2040/README.md
Normal file
@ -0,0 +1 @@
|
||||
# RP2040 Hardware Interface
|
93
Marlin/src/HAL/RP2040/Servo.cpp
Normal file
93
Marlin/src/HAL/RP2040/Servo.cpp
Normal 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__
|
77
Marlin/src/HAL/RP2040/Servo.h
Normal file
77
Marlin/src/HAL/RP2040/Servo.h
Normal 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
|
33
Marlin/src/HAL/RP2040/arduino_extras.cpp
Normal file
33
Marlin/src/HAL/RP2040/arduino_extras.cpp
Normal 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__
|
29
Marlin/src/HAL/RP2040/arduino_extras.h
Normal file
29
Marlin/src/HAL/RP2040/arduino_extras.h
Normal 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);
|
88
Marlin/src/HAL/RP2040/eeprom_flash.cpp
Normal file
88
Marlin/src/HAL/RP2040/eeprom_flash.cpp
Normal 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__
|
79
Marlin/src/HAL/RP2040/eeprom_wired.cpp
Normal file
79
Marlin/src/HAL/RP2040/eeprom_wired.cpp
Normal 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__
|
60
Marlin/src/HAL/RP2040/endstop_interrupts.h
Normal file
60
Marlin/src/HAL/RP2040/endstop_interrupts.h
Normal 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));
|
||||
}
|
43
Marlin/src/HAL/RP2040/fast_pwm.cpp
Normal file
43
Marlin/src/HAL/RP2040/fast_pwm.cpp
Normal 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__
|
32
Marlin/src/HAL/RP2040/fastio.cpp
Normal file
32
Marlin/src/HAL/RP2040/fastio.cpp
Normal 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__
|
87
Marlin/src/HAL/RP2040/fastio.h
Normal file
87
Marlin/src/HAL/RP2040/fastio.h
Normal 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
|
22
Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h
Normal file
22
Marlin/src/HAL/RP2040/inc/Conditionals_LCD.h
Normal 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
|
35
Marlin/src/HAL/RP2040/inc/Conditionals_adv.h
Normal file
35
Marlin/src/HAL/RP2040/inc/Conditionals_adv.h
Normal 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
|
29
Marlin/src/HAL/RP2040/inc/Conditionals_post.h
Normal file
29
Marlin/src/HAL/RP2040/inc/Conditionals_post.h
Normal 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
|
22
Marlin/src/HAL/RP2040/inc/Conditionals_type.h
Normal file
22
Marlin/src/HAL/RP2040/inc/Conditionals_type.h
Normal 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
|
60
Marlin/src/HAL/RP2040/inc/SanityCheck.h
Normal file
60
Marlin/src/HAL/RP2040/inc/SanityCheck.h
Normal 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
|
136
Marlin/src/HAL/RP2040/msc_sd.cpp
Normal file
136
Marlin/src/HAL/RP2040/msc_sd.cpp
Normal 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__
|
24
Marlin/src/HAL/RP2040/msc_sd.h
Normal file
24
Marlin/src/HAL/RP2040/msc_sd.h
Normal 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();
|
146
Marlin/src/HAL/RP2040/pinsDebug.h
Normal file
146
Marlin/src/HAL/RP2040/pinsDebug.h
Normal 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 getValidPinMode(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 isAnalogPin(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 printPinPort(const pin_t Ard_num) {
|
||||
SERIAL_ECHOPGM("Pin: ");
|
||||
SERIAL_ECHO(Ard_num);
|
||||
}
|
||||
|
||||
bool pwm_status(const pin_t Ard_num) {
|
||||
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
|
||||
}
|
||||
|
||||
void printPinPWM(const pin_t Ard_num) {
|
||||
if (PWM_PIN(Ard_num)) {
|
||||
}
|
||||
}
|
38
Marlin/src/HAL/RP2040/spi_pins.h
Normal file
38
Marlin/src/HAL/RP2040/spi_pins.h
Normal 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
|
126
Marlin/src/HAL/RP2040/timers.cpp
Normal file
126
Marlin/src/HAL/RP2040/timers.cpp
Normal 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__
|
177
Marlin/src/HAL/RP2040/timers.h
Normal file
177
Marlin/src/HAL/RP2040/timers.h
Normal 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
|
@ -108,7 +108,6 @@
|
||||
SPI.beginTransaction(spiConfig);
|
||||
SPI.transfer(buf, nbyte);
|
||||
SPI.endTransaction();
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -22,41 +22,57 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD21 HAL developed by Bart Meijer (brupje)
|
||||
* Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
|
||||
* Pins Debugging for SAMD21
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0)
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
|
||||
#define isValidPin(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL)
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P)!=-1)
|
||||
#define pwm_status(pin) digitalPinHasPWM(pin)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1)
|
||||
#define pwm_status(P) digitalPinHasPWM(P)
|
||||
#define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
// uses pin index
|
||||
#define M43_NEVER_TOUCH(Q) ((Q) >= 75)
|
||||
|
||||
bool getValidPinMode(int8_t pin) { // 1: output, 0: input
|
||||
bool getValidPinMode(const int8_t pin) { // 1: output, 0: input
|
||||
const EPortType samdport = g_APinDescription[pin].ulPort;
|
||||
const uint32_t samdpin = g_APinDescription[pin].ulPin;
|
||||
return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN;
|
||||
}
|
||||
|
||||
void printPinPWM(int32_t pin) {
|
||||
void printPinPWM(const int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
|
||||
//SERIAL_ECHOPGM("PWM = ", duty);
|
||||
}
|
||||
}
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
||||
/**
|
||||
* SAMD21 Board pin| PORT | Label
|
||||
* ----------------+--------+-------
|
||||
|
@ -22,40 +22,57 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
|
||||
* Pins Debugging for SAMD51
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL PINS_COUNT
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0)
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
|
||||
#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P)!=-1)
|
||||
#define pwm_status(pin) digitalPinHasPWM(pin)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) != -1)
|
||||
#define pwm_status(P) digitalPinHasPWM(P)
|
||||
#define MULTI_NAME_PAD 27 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||
// uses pin index
|
||||
#define M43_NEVER_TOUCH(Q) ((Q) >= 75)
|
||||
|
||||
bool getValidPinMode(int8_t pin) { // 1: output, 0: input
|
||||
bool getValidPinMode(const int8_t pin) { // 1: output, 0: input
|
||||
const EPortType samdport = g_APinDescription[pin].ulPort;
|
||||
const uint32_t samdpin = g_APinDescription[pin].ulPin;
|
||||
return PORT->Group[samdport].DIR.reg & MASK(samdpin) || (PORT->Group[samdport].PINCFG[samdpin].reg & (PORT_PINCFG_INEN | PORT_PINCFG_PULLEN)) == PORT_PINCFG_PULLEN;
|
||||
}
|
||||
|
||||
void printPinPWM(int32_t pin) {
|
||||
void printPinPWM(const int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
|
||||
//SERIAL_ECHOPGM("PWM = ", duty);
|
||||
}
|
||||
}
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
||||
/**
|
||||
* AGCM4 Board pin | PORT | Label
|
||||
* ----------------+--------+-------
|
||||
|
@ -21,6 +21,26 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Pins Debugging for STM32
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#include <Arduino.h>
|
||||
|
||||
#ifndef NUM_DIGITAL_PINS
|
||||
@ -34,11 +54,11 @@
|
||||
* 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
|
||||
* A - 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
|
||||
@ -98,15 +118,11 @@ const XrefInfo pin_xref[] PROGMEM = {
|
||||
#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 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))
|
||||
|
||||
#if NUM_ANALOG_FIRST >= NUM_DIGITAL_PINS
|
||||
#define HAS_HIGH_ANALOG_PINS 1
|
||||
@ -116,10 +132,10 @@ const XrefInfo pin_xref[] PROGMEM = {
|
||||
#endif
|
||||
#define NUMBER_PINS_TOTAL ((NUM_DIGITAL_PINS) + TERN0(HAS_HIGH_ANALOG_PINS, NUM_ANALOG_INPUTS))
|
||||
#define isValidPin(P) (WITHIN(P, 0, (NUM_DIGITAL_PINS) - 1) || TERN0(HAS_HIGH_ANALOG_PINS, WITHIN(P, NUM_ANALOG_FIRST, NUM_ANALOG_LAST)))
|
||||
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
|
||||
#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads
|
||||
#define printPinNumber(Q)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define digitalPinToAnalogIndex(ANUM) -1 // will report analog pin number in the print port routine
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine
|
||||
|
||||
// x is a variable used to search pin_array
|
||||
#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital)
|
||||
@ -130,27 +146,27 @@ const XrefInfo pin_xref[] PROGMEM = {
|
||||
//
|
||||
// Pin Mapping for M43
|
||||
//
|
||||
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
|
||||
#define GET_PIN_MAP_PIN_M43(x) pin_xref[x].Ard_num
|
||||
|
||||
#ifndef M43_NEVER_TOUCH
|
||||
#define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
|
||||
#define _M43_NEVER_TOUCH(x) WITHIN(x, 9, 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
|
||||
#ifdef KILL_PIN
|
||||
#define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
|
||||
#define M43_NEVER_TOUCH(x) m43_never_touch(x)
|
||||
|
||||
bool m43_never_touch(const pin_t Index) {
|
||||
bool m43_never_touch(const pin_t index) {
|
||||
static pin_t M43_kill_index = -1;
|
||||
if (M43_kill_index < 0)
|
||||
for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
|
||||
if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
|
||||
return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
|
||||
return _M43_NEVER_TOUCH(index) || index == M43_kill_index; // KILL_PIN and SERIAL/USB
|
||||
}
|
||||
#else
|
||||
#define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
|
||||
#define M43_NEVER_TOUCH(index) _M43_NEVER_TOUCH(index)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
uint8_t get_pin_mode(const pin_t Ard_num) {
|
||||
const PinName dp = digitalPinToPinName(Ard_num);
|
||||
uint8_t get_pin_mode(const pin_t pin) {
|
||||
const PinName dp = digitalPinToPinName(pin);
|
||||
uint32_t ll_pin = STM_LL_GPIO_PIN(dp);
|
||||
GPIO_TypeDef *port = get_GPIO_Port(STM_PORT(dp));
|
||||
uint32_t mode = LL_GPIO_GetPinMode(port, ll_pin);
|
||||
@ -164,41 +180,41 @@ uint8_t get_pin_mode(const pin_t Ard_num) {
|
||||
}
|
||||
}
|
||||
|
||||
bool getValidPinMode(const pin_t Ard_num) {
|
||||
const uint8_t pin_mode = get_pin_mode(Ard_num);
|
||||
bool getValidPinMode(const pin_t pin) {
|
||||
const uint8_t pin_mode = get_pin_mode(pin);
|
||||
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
|
||||
}
|
||||
|
||||
int8_t digital_pin_to_analog_pin(const pin_t Ard_num) {
|
||||
if (WITHIN(Ard_num, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))
|
||||
return Ard_num - NUM_ANALOG_FIRST;
|
||||
int8_t digital_pin_to_analog_pin(const pin_t pin) {
|
||||
if (WITHIN(pin, NUM_ANALOG_FIRST, NUM_ANALOG_LAST))
|
||||
return pin - NUM_ANALOG_FIRST;
|
||||
|
||||
const int8_t ind = digitalPinToAnalogIndex(Ard_num);
|
||||
const int8_t ind = digitalPinToAnalogIndex(pin);
|
||||
return (ind < NUM_ANALOG_INPUTS) ? ind : -1;
|
||||
}
|
||||
|
||||
bool isAnalogPin(const pin_t Ard_num) {
|
||||
return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
|
||||
bool isAnalogPin(const pin_t pin) {
|
||||
return get_pin_mode(pin) == MODE_PIN_ANALOG;
|
||||
}
|
||||
|
||||
bool is_digital(const pin_t Ard_num) {
|
||||
const uint8_t pin_mode = get_pin_mode(pin_array[Ard_num].pin);
|
||||
bool is_digital(const pin_t pin) {
|
||||
const uint8_t pin_mode = get_pin_mode(pin_array[pin].pin);
|
||||
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
|
||||
}
|
||||
|
||||
void printPinPort(const pin_t Ard_num) {
|
||||
void printPinPort(const pin_t pin) {
|
||||
char buffer[16];
|
||||
pin_t Index;
|
||||
for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
|
||||
if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
|
||||
pin_t index;
|
||||
for (index = 0; index < NUMBER_PINS_TOTAL; index++)
|
||||
if (pin == GET_PIN_MAP_PIN_M43(index)) break;
|
||||
|
||||
const char * ppa = pin_xref[Index].Port_pin_alpha;
|
||||
const char * ppa = pin_xref[index].Port_pin_alpha;
|
||||
sprintf_P(buffer, PSTR("%s"), ppa);
|
||||
SERIAL_ECHO(buffer);
|
||||
if (ppa[3] == '\0') SERIAL_CHAR(' ');
|
||||
|
||||
// print analog pin number
|
||||
const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
|
||||
const int8_t Port_pin = digital_pin_to_analog_pin(pin);
|
||||
if (Port_pin >= 0) {
|
||||
sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
|
||||
SERIAL_ECHO(buffer);
|
||||
@ -208,8 +224,8 @@ void printPinPort(const pin_t Ard_num) {
|
||||
SERIAL_ECHO_SP(7);
|
||||
|
||||
// Print number to be used with M42
|
||||
int calc_p = Ard_num;
|
||||
if (Ard_num > NUM_DIGITAL_PINS) {
|
||||
int calc_p = pin;
|
||||
if (pin > NUM_DIGITAL_PINS) {
|
||||
calc_p -= NUM_ANALOG_FIRST;
|
||||
if (calc_p > 7) calc_p += 8;
|
||||
}
|
||||
@ -222,15 +238,15 @@ void printPinPort(const pin_t Ard_num) {
|
||||
}
|
||||
}
|
||||
|
||||
bool pwm_status(const pin_t Ard_num) {
|
||||
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
|
||||
bool pwm_status(const pin_t pin) {
|
||||
return get_pin_mode(pin) == MODE_PIN_ALT;
|
||||
}
|
||||
|
||||
void printPinPWM(const pin_t Ard_num) {
|
||||
void printPinPWM(const pin_t pin) {
|
||||
#ifndef STM32F1xx
|
||||
if (pwm_status(Ard_num)) {
|
||||
if (pwm_status(pin)) {
|
||||
uint32_t alt_all = 0;
|
||||
const PinName dp = digitalPinToPinName(Ard_num);
|
||||
const PinName dp = digitalPinToPinName(pin);
|
||||
pin_t pin_number = uint8_t(PIN_NUM(dp));
|
||||
const bool over_7 = pin_number >= 8;
|
||||
const uint8_t ind = over_7 ? 1 : 0;
|
||||
|
@ -22,11 +22,23 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* Support routines for MAPLE_STM32F1
|
||||
*/
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
* Pins Debugging for Maple STM32F1
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#ifndef BOARD_NR_GPIO_PINS // Only in MAPLE_STM32F1
|
||||
@ -39,11 +51,11 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
|
||||
|
||||
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
|
||||
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
|
||||
#define isValidPin(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
|
||||
#define getPinByIndex(p) pin_t(pin_array[p].pin)
|
||||
#define digitalRead_mod(p) extDigitalRead(p)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define isValidPin(P) (P >= 0 && P < BOARD_NR_GPIO_PINS)
|
||||
#define getPinByIndex(x) pin_t(pin_array[x].pin)
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
@ -78,8 +90,8 @@ bool getValidPinMode(const pin_t pin) {
|
||||
return isValidPin(pin) && !IS_INPUT(pin);
|
||||
}
|
||||
|
||||
bool getPinIsDigitalByIndex(const int16_t array_pin) {
|
||||
const pin_t pin = getPinByIndex(array_pin);
|
||||
bool getPinIsDigitalByIndex(const int16_t index) {
|
||||
const pin_t pin = getPinByIndex(index);
|
||||
return (!isAnalogPin(pin)
|
||||
#ifdef NUM_ANALOG_INPUTS
|
||||
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
|
||||
|
@ -1 +1,71 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2019 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
|
||||
|
||||
#error "PINS_DEBUGGING is not yet supported for Teensy 3.1 / 3.2!"
|
||||
|
||||
/**
|
||||
* Pins Debugging for ESP32
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
#define digitalRead_mod(P) extDigitalRead(P)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
|
||||
#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
|
||||
bool pwm_status(const pin_t) { return false; }
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
||||
static bool getValidPinMode(const pin_t pin) {
|
||||
return isValidPin(pin) /* && !IS_INPUT(pin) */ ;
|
||||
}
|
||||
|
||||
void printPinPWM(const int32_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
|
||||
//SERIAL_ECHOPGM("PWM = ", duty);
|
||||
}
|
||||
}
|
||||
|
@ -48,3 +48,7 @@
|
||||
#if USING_PULLDOWNS
|
||||
#error "PULLDOWN pin mode is not available for Teensy 3.5/3.6."
|
||||
#endif
|
||||
|
||||
#if ENABLED(PINS_DEBUGGING)
|
||||
#error "PINS_DEBUGGING is not yet supported for Teensy 3.5/3.6. Needs is_output(pin), etc."
|
||||
#endif
|
||||
|
@ -22,7 +22,23 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* HAL Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
|
||||
* Pins Debugging for Teensy 3.5 (MK64FX512) and Teensy 3.6 (MK66FX1M0)
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
@ -53,6 +69,15 @@
|
||||
#define TPM1_CH1_PIN 17
|
||||
#endif
|
||||
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
|
||||
#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P))
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
|
||||
#define isAnalogPin(P) ((P) >= analogInputToDigitalPin(0) && (P) <= analogInputToDigitalPin(9)) || ((P) >= analogInputToDigitalPin(12) && (P) <= analogInputToDigitalPin(20))
|
||||
|
||||
void printAnalogPin(char buffer[], int8_t pin) {
|
||||
@ -77,7 +102,7 @@ void analog_pin_state(char buffer[], int8_t pin) {
|
||||
* Print a pin's PWM status.
|
||||
* Return true if it's currently a PWM pin.
|
||||
*/
|
||||
bool pwm_status(int8_t pin) {
|
||||
bool pwm_status(const int8_t pin) {
|
||||
char buffer[20]; // for the sprintf statements
|
||||
switch (pin) {
|
||||
FTM_CASE(0,0);
|
||||
@ -108,4 +133,6 @@ bool pwm_status(int8_t pin) {
|
||||
SERIAL_ECHOPGM(" ");
|
||||
}
|
||||
|
||||
void printPinPWM(uint8_t pin) { /* TODO */ }
|
||||
void printPinPWM(const pin_t) { /* TODO */ }
|
||||
|
||||
void printPinPort(const pin_t) {}
|
||||
|
@ -22,25 +22,40 @@
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* HAL Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
|
||||
* Pins Debugging for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#warning "PINS_DEBUGGING is not fully supported for Teensy 4.0 / 4.1 so 'M43' may cause hangs."
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
|
||||
#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinByIndex(p) pin_array[p].pin
|
||||
#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
|
||||
#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
|
||||
#define digitalPinToAnalogIndex(p) int(p - analogInputToDigitalPin(0))
|
||||
#define getValidPinMode(PIN) (isValidPin(pin) && IS_OUTPUT(pin))
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define digitalPinToAnalogIndex(P) int(P - analogInputToDigitalPin(0))
|
||||
#define getValidPinMode(P) (isValidPin(P) && IS_OUTPUT(P))
|
||||
#define isValidPin(P) (P >= 0 && P < pin_t(NUMBER_PINS_TOTAL))
|
||||
#define isAnalogPin(P) (pin_t(P) >= analogInputToDigitalPin(0) && pin_t(P) <= analogInputToDigitalPin(13)) || (pin_t(P) >= analogInputToDigitalPin(14) && pin_t(P) <= analogInputToDigitalPin(17))
|
||||
#define digitalRead_mod(P) extDigitalRead(P) // AVR digitalRead disabled PWM before it read the pin
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%02d"), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
struct pwm_pin_info_struct {
|
||||
uint8_t type; // 0=no pwm, 1=flexpwm, 2=quad
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
|
@ -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
|
||||
//
|
||||
|
@ -188,3 +188,16 @@
|
||||
|| HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE)
|
||||
#define HAS_DIAG_PINS 1
|
||||
#endif
|
||||
|
||||
// Hybrid Threshold ranges
|
||||
#define THRS_TMC2100 65535
|
||||
#define THRS_TMC2130 65535
|
||||
#define THRS_TMC2160 255
|
||||
#define THRS_TMC2208 255
|
||||
#define THRS_TMC2209 255
|
||||
#define THRS_TMC2660 65535
|
||||
#define THRS_TMC5130 65535
|
||||
#define THRS_TMC5160 65535
|
||||
|
||||
#define _DRIVER_THRS(V) CAT(THRS_, V)
|
||||
#define STEPPER_MAX_THRS(S) _DRIVER_THRS(S##_DRIVER_TYPE)
|
||||
|
@ -324,6 +324,7 @@
|
||||
#define STR_TEMPERATURE_UNITS "Temperature Units"
|
||||
#define STR_USER_THERMISTORS "User thermistors"
|
||||
#define STR_DELAYED_POWEROFF "Delayed poweroff"
|
||||
#define STR_STORED_MACROS "Stored macros"
|
||||
|
||||
//
|
||||
// General axis names
|
||||
|
@ -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);
|
||||
|
||||
|
@ -30,23 +30,20 @@
|
||||
|
||||
CancelObject cancelable;
|
||||
|
||||
int8_t CancelObject::object_count, // = 0
|
||||
CancelObject::active_object = -1;
|
||||
uint32_t CancelObject::canceled; // = 0x0000
|
||||
bool CancelObject::skipping; // = false
|
||||
cancel_state_t CancelObject::state;
|
||||
|
||||
void CancelObject::set_active_object(const int8_t obj) {
|
||||
active_object = obj;
|
||||
state.active_object = obj;
|
||||
if (WITHIN(obj, 0, 31)) {
|
||||
if (obj >= object_count) object_count = obj + 1;
|
||||
skipping = TEST(canceled, obj);
|
||||
if (obj >= state.object_count) state.object_count = obj + 1;
|
||||
state.skipping = TEST(state.canceled, obj);
|
||||
}
|
||||
else
|
||||
skipping = false;
|
||||
state.skipping = false;
|
||||
|
||||
#if ALL(HAS_STATUS_MESSAGE, CANCEL_OBJECTS_REPORTING)
|
||||
if (active_object >= 0)
|
||||
ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', active_object));
|
||||
if (state.active_object >= 0)
|
||||
ui.set_status(MString<30>(GET_TEXT_F(MSG_PRINTING_OBJECT), ' ', state.active_object));
|
||||
else
|
||||
ui.reset_status();
|
||||
#endif
|
||||
@ -54,29 +51,29 @@ void CancelObject::set_active_object(const int8_t obj) {
|
||||
|
||||
void CancelObject::cancel_object(const int8_t obj) {
|
||||
if (WITHIN(obj, 0, 31)) {
|
||||
SBI(canceled, obj);
|
||||
if (obj == active_object) skipping = true;
|
||||
SBI(state.canceled, obj);
|
||||
if (obj == state.active_object) state.skipping = true;
|
||||
}
|
||||
}
|
||||
|
||||
void CancelObject::uncancel_object(const int8_t obj) {
|
||||
if (WITHIN(obj, 0, 31)) {
|
||||
CBI(canceled, obj);
|
||||
if (obj == active_object) skipping = false;
|
||||
CBI(state.canceled, obj);
|
||||
if (obj == state.active_object) state.skipping = false;
|
||||
}
|
||||
}
|
||||
|
||||
void CancelObject::report() {
|
||||
if (active_object >= 0)
|
||||
SERIAL_ECHO_MSG("Active Object: ", active_object);
|
||||
if (state.active_object >= 0)
|
||||
SERIAL_ECHO_MSG("Active Object: ", state.active_object);
|
||||
|
||||
if (canceled) {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Canceled:");
|
||||
for (int i = 0; i < object_count; i++)
|
||||
if (TEST(canceled, i)) { SERIAL_CHAR(' '); SERIAL_ECHO(i); }
|
||||
SERIAL_EOL();
|
||||
}
|
||||
if (state.canceled == 0x0000) return;
|
||||
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Canceled:");
|
||||
for (int i = 0; i < state.object_count; i++)
|
||||
if (TEST(state.canceled, i)) { SERIAL_CHAR(' '); SERIAL_ECHO(i); }
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
#endif // CANCEL_OBJECTS
|
||||
|
@ -23,19 +23,23 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
typedef struct CancelState {
|
||||
bool skipping = false;
|
||||
int8_t object_count = 0, active_object = 0;
|
||||
uint32_t canceled = 0x0000;
|
||||
} cancel_state_t;
|
||||
|
||||
class CancelObject {
|
||||
public:
|
||||
static bool skipping;
|
||||
static int8_t object_count, active_object;
|
||||
static uint32_t canceled;
|
||||
static void set_active_object(const int8_t obj);
|
||||
static cancel_state_t state;
|
||||
static void set_active_object(const int8_t obj=state.active_object);
|
||||
static void cancel_object(const int8_t obj);
|
||||
static void uncancel_object(const int8_t obj);
|
||||
static void report();
|
||||
static bool is_canceled(const int8_t obj) { return TEST(canceled, obj); }
|
||||
static bool is_canceled(const int8_t obj) { return TEST(state.canceled, obj); }
|
||||
static void clear_active_object() { set_active_object(-1); }
|
||||
static void cancel_active_object() { cancel_object(active_object); }
|
||||
static void reset() { canceled = 0x0000; object_count = 0; clear_active_object(); }
|
||||
static void cancel_active_object() { cancel_object(state.active_object); }
|
||||
static void reset() { state.canceled = 0x0000; state.object_count = 0; clear_active_object(); }
|
||||
};
|
||||
|
||||
extern CancelObject cancelable;
|
||||
|
@ -36,7 +36,7 @@
|
||||
#include "../module/stepper.h"
|
||||
#include "../gcode/parser.h"
|
||||
|
||||
#include "../feature/babystep.h"
|
||||
#include "babystep.h"
|
||||
|
||||
#include <Wire.h>
|
||||
|
||||
|
@ -31,7 +31,7 @@
|
||||
#include "leds.h"
|
||||
|
||||
#if ANY(CASE_LIGHT_USE_RGB_LED, CASE_LIGHT_USE_NEOPIXEL)
|
||||
#include "../../feature/caselight.h"
|
||||
#include "../caselight.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(LED_COLOR_PRESETS)
|
||||
|
@ -43,7 +43,7 @@ MMU2 mmu2;
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
#include "../../feature/host_actions.h"
|
||||
#include "../host_actions.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
|
@ -28,7 +28,7 @@
|
||||
|
||||
#if HAS_PRUSA_MMU3
|
||||
|
||||
#include "../../feature/runout.h"
|
||||
#include "../runout.h"
|
||||
#include "mmu3_fsensor.h"
|
||||
|
||||
namespace MMU3 {
|
||||
|
@ -34,7 +34,7 @@
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/temperature.h"
|
||||
|
||||
#include "../../feature/pause.h"
|
||||
#include "../pause.h"
|
||||
#include "../../libs/nozzle.h"
|
||||
#include "mmu3_marlin.h"
|
||||
|
||||
|
@ -43,7 +43,7 @@
|
||||
|
||||
#include "../../core/language.h"
|
||||
#include "../../gcode/gcode.h"
|
||||
#include "../../feature/host_actions.h"
|
||||
#include "../host_actions.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
#include "../../lcd/menu/menu.h"
|
||||
#include "../../lcd/menu/menu_item.h"
|
||||
|
@ -99,7 +99,7 @@ PrintJobRecovery recovery;
|
||||
/**
|
||||
* Clear the recovery info
|
||||
*/
|
||||
void PrintJobRecovery::init() { memset(&info, 0, sizeof(info)); }
|
||||
void PrintJobRecovery::init() { info = {}; }
|
||||
|
||||
/**
|
||||
* Enable or disable then call changed()
|
||||
@ -215,6 +215,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW
|
||||
info.zraise = zraise;
|
||||
info.flag.raised = raised; // Was Z raised before power-off?
|
||||
|
||||
TERN_(CANCEL_OBJECTS, info.cancel_state = cancelable.state);
|
||||
TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat);
|
||||
TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset);
|
||||
TERN_(HAS_WORKSPACE_OFFSET, info.workspace_offset = workspace_offset);
|
||||
@ -575,6 +576,11 @@ void PrintJobRecovery::resume() {
|
||||
// Restore E position with G92.9
|
||||
PROCESS_SUBCOMMANDS_NOW(TS(F("G92.9E"), p_float_t(resume_pos.e, 3)));
|
||||
|
||||
#if ENABLED(CANCEL_OBJECTS)
|
||||
cancelable.state = info.cancel_state;
|
||||
cancelable.set_active_object(); // Sets the status message
|
||||
#endif
|
||||
|
||||
TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat);
|
||||
TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset);
|
||||
TERN_(HAS_WORKSPACE_OFFSET, workspace_offset = info.workspace_offset);
|
||||
@ -613,6 +619,14 @@ void PrintJobRecovery::resume() {
|
||||
|
||||
DEBUG_ECHOLNPGM("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : "");
|
||||
|
||||
#if ENABLED(CANCEL_OBJECTS)
|
||||
const cancel_state_t cs = info.cancel_state;
|
||||
DEBUG_ECHOPGM("Canceled:");
|
||||
for (int i = 0; i < cs.object_count; i++)
|
||||
if (TEST(cs.canceled, i)) { DEBUG_CHAR(' '); DEBUG_ECHO(i); }
|
||||
DEBUG_EOL();
|
||||
#endif
|
||||
|
||||
#if ENABLED(GCODE_REPEAT_MARKERS)
|
||||
const uint8_t ind = info.stored_repeat.count();
|
||||
DEBUG_ECHOLNPGM("repeat markers: ", ind);
|
||||
|
@ -30,12 +30,16 @@
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(CANCEL_OBJECTS)
|
||||
#include "cancel_object.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(GCODE_REPEAT_MARKERS)
|
||||
#include "../feature/repeat.h"
|
||||
#include "repeat.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
#include "../feature/mixing.h"
|
||||
#include "mixing.h"
|
||||
#endif
|
||||
|
||||
#if !defined(POWER_LOSS_STATE) && PIN_EXISTS(POWER_LOSS)
|
||||
@ -64,6 +68,11 @@ typedef struct {
|
||||
|
||||
float zraise;
|
||||
|
||||
// Canceled objects
|
||||
#if ENABLED(CANCEL_OBJECTS)
|
||||
cancel_state_t cancel_state;
|
||||
#endif
|
||||
|
||||
// Repeat information
|
||||
#if ENABLED(GCODE_REPEAT_MARKERS)
|
||||
Repeat stored_repeat;
|
||||
|
@ -59,7 +59,7 @@ bool FilamentMonitorBase::enabled = true,
|
||||
// Filament Runout event handler
|
||||
//
|
||||
#include "../MarlinCore.h"
|
||||
#include "../feature/pause.h"
|
||||
#include "pause.h"
|
||||
#include "../gcode/queue.h"
|
||||
|
||||
#if ENABLED(HOST_ACTION_COMMANDS)
|
||||
|
@ -30,7 +30,7 @@
|
||||
#include "../module/planner.h"
|
||||
#include "../module/stepper.h" // for block_t
|
||||
#include "../gcode/queue.h"
|
||||
#include "../feature/pause.h" // for did_pause_print
|
||||
#include "pause.h" // for did_pause_print
|
||||
#include "../MarlinCore.h" // for printingIsActive()
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
|
@ -35,7 +35,7 @@
|
||||
#endif
|
||||
|
||||
#if ENABLED(I2C_AMMETER)
|
||||
#include "../feature/ammeter.h"
|
||||
#include "ammeter.h"
|
||||
#endif
|
||||
|
||||
SpindleLaser cutter;
|
||||
|
@ -77,8 +77,8 @@ class TMCStorage {
|
||||
|
||||
struct {
|
||||
OPTCODE(HAS_STEALTHCHOP, bool stealthChop_enabled = false)
|
||||
OPTCODE(HYBRID_THRESHOLD, uint8_t hybrid_thrs = 0)
|
||||
OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0)
|
||||
OPTCODE(HYBRID_THRESHOLD, uint16_t hybrid_thrs = 0)
|
||||
OPTCODE(USE_SENSORLESS, int16_t homing_thrs = 0)
|
||||
} stored;
|
||||
};
|
||||
|
||||
|
@ -102,7 +102,7 @@
|
||||
#define G26_OK false
|
||||
#define G26_ERR true
|
||||
|
||||
#include "../../gcode/gcode.h"
|
||||
#include "../gcode.h"
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
|
@ -53,7 +53,7 @@
|
||||
* 41 - Counter-Clockwise M4
|
||||
* 50 - Clockwise M5
|
||||
* 51 - Counter-Clockwise M5
|
||||
**/
|
||||
*/
|
||||
void GcodeSuite::G35() {
|
||||
|
||||
DEBUG_SECTION(log_G35, "G35", DEBUGGING(LEVELING));
|
||||
|
@ -43,40 +43,40 @@
|
||||
* P : Flag to put the probe at the given point
|
||||
*/
|
||||
void GcodeSuite::G42() {
|
||||
if (MOTION_CONDITIONS) {
|
||||
const bool hasI = parser.seenval('I');
|
||||
const int8_t ix = hasI ? parser.value_int() : 0;
|
||||
const bool hasJ = parser.seenval('J');
|
||||
const int8_t iy = hasJ ? parser.value_int() : 0;
|
||||
if (!MOTION_CONDITIONS) return;
|
||||
|
||||
if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) {
|
||||
SERIAL_ECHOLNPGM(STR_ERR_MESH_XY);
|
||||
return;
|
||||
}
|
||||
const bool hasI = parser.seenval('I');
|
||||
const int8_t ix = hasI ? parser.value_int() : 0;
|
||||
const bool hasJ = parser.seenval('J');
|
||||
const int8_t iy = hasJ ? parser.value_int() : 0;
|
||||
|
||||
// Move to current_position, as modified by I, J, P parameters
|
||||
destination = current_position;
|
||||
|
||||
if (hasI) destination.x = bedlevel.get_mesh_x(ix);
|
||||
if (hasJ) destination.y = bedlevel.get_mesh_y(iy);
|
||||
|
||||
#if HAS_PROBE_XY_OFFSET
|
||||
if (parser.seen_test('P')) {
|
||||
if (hasI) destination.x -= probe.offset_xy.x;
|
||||
if (hasJ) destination.y -= probe.offset_xy.y;
|
||||
}
|
||||
#endif
|
||||
|
||||
const feedRate_t fval = parser.linearval('F'),
|
||||
fr_mm_s = MMM_TO_MMS(fval > 0 ? fval : 0.0f);
|
||||
|
||||
// SCARA kinematic has "safe" XY raw moves
|
||||
#if IS_SCARA
|
||||
prepare_internal_fast_move_to_destination(fr_mm_s);
|
||||
#else
|
||||
prepare_internal_move_to_destination(fr_mm_s);
|
||||
#endif
|
||||
if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) {
|
||||
SERIAL_ECHOLNPGM(STR_ERR_MESH_XY);
|
||||
return;
|
||||
}
|
||||
|
||||
// Move to current_position, as modified by I, J, P parameters
|
||||
destination = current_position;
|
||||
|
||||
if (hasI) destination.x = bedlevel.get_mesh_x(ix);
|
||||
if (hasJ) destination.y = bedlevel.get_mesh_y(iy);
|
||||
|
||||
#if HAS_PROBE_XY_OFFSET
|
||||
if (parser.seen_test('P')) {
|
||||
if (hasI) destination.x -= probe.offset_xy.x;
|
||||
if (hasJ) destination.y -= probe.offset_xy.y;
|
||||
}
|
||||
#endif
|
||||
|
||||
const feedRate_t fval = parser.linearval('F'),
|
||||
fr_mm_s = MMM_TO_MMS(fval > 0 ? fval : 0.0f);
|
||||
|
||||
// SCARA kinematic has "safe" XY raw moves
|
||||
#if IS_SCARA
|
||||
prepare_internal_fast_move_to_destination(fr_mm_s);
|
||||
#else
|
||||
prepare_internal_move_to_destination(fr_mm_s);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAS_MESH
|
||||
|
@ -212,7 +212,28 @@ void GcodeSuite::G34() {
|
||||
// Probe a Z height for each stepper.
|
||||
// Probing sanity check is disabled, as it would trigger even in normal cases because
|
||||
// current_position.z has been manually altered in the "dirty trick" above.
|
||||
const float z_probed_height = probe.probe_at_point(DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), raise_after, 0, true, false, (Z_PROBE_LOW_POINT) - z_probe * 0.5f, z_probe * 0.5f);
|
||||
|
||||
if (DEBUGGING(LEVELING))
|
||||
DEBUG_ECHOLNPGM(
|
||||
"Z_PROBE_LOW_POINT: ", p_float_t(Z_PROBE_LOW_POINT, 2),
|
||||
"z_probe: ", p_float_t(z_probe, 2),
|
||||
"Probe Tgt: ", p_float_t((Z_PROBE_LOW_POINT) - z_probe * 0.5f, 2)
|
||||
);
|
||||
|
||||
const float z_probed_height = probe.probe_at_point(
|
||||
DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), // xy
|
||||
raise_after, // raise_after
|
||||
(DEBUGGING(LEVELING) || DEBUGGING(INFO)) ? 3 : 0, // verbose_level
|
||||
true, false, // probe_relative, sanity_check
|
||||
(Z_PROBE_LOW_POINT) - (z_probe * 0.5f), // z_min_point
|
||||
Z_TWEEN_SAFE_CLEARANCE // z_clearance
|
||||
);
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y);
|
||||
DEBUG_ECHOLNPGM("Height = ", z_probed_height);
|
||||
}
|
||||
|
||||
if (isnan(z_probed_height)) {
|
||||
SERIAL_ECHOLNPGM(STR_ERR_PROBING_FAILED);
|
||||
LCD_MESSAGE(MSG_LCD_PROBING_FAILED);
|
||||
@ -236,7 +257,12 @@ void GcodeSuite::G34() {
|
||||
// Adapt the next probe clearance height based on the new measurements.
|
||||
// Safe_height = lowest distance to bed (= highest measurement) plus highest measured misalignment.
|
||||
z_maxdiff = z_measured_max - z_measured_min;
|
||||
z_probe = (Z_TWEEN_SAFE_CLEARANCE + zoffs) + z_measured_max + z_maxdiff; //Not sure we need z_maxdiff, but leaving it in for safety.
|
||||
|
||||
// The intent of the line below seems to be to clamp the probe depth on successive iterations of G34, but in reality if the amplification
|
||||
// factor is not completely accurate, this was causing probing to fail as the probe stopped fractions of a mm from the trigger point
|
||||
// on the second iteration very reliably. This may be restored with an uncertainty factor at some point, however its usefulness after
|
||||
// all probe points have seen a successful probe is questionable.
|
||||
//z_probe = (Z_TWEEN_SAFE_CLEARANCE + zoffs) + z_measured_max + z_maxdiff; // Not sure we need z_maxdiff, but leaving it in for safety.
|
||||
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
// Replace the initial values in z_measured with calculated heights at
|
||||
@ -401,7 +427,15 @@ void GcodeSuite::G34() {
|
||||
// Use the probed height from the last iteration to determine the Z height.
|
||||
// z_measured_min is used, because all steppers are aligned to z_measured_min.
|
||||
// Ideally, this would be equal to the 'z_probe * 0.5f' which was added earlier.
|
||||
current_position.z -= z_measured_min - (Z_TWEEN_SAFE_CLEARANCE + zoffs); //we shouldn't want to subtract the clearance from here right? (Depends if we added it further up)
|
||||
if (DEBUGGING(LEVELING))
|
||||
DEBUG_ECHOLNPGM(
|
||||
"z_measured_min: ", p_float_t(z_measured_min, 2),
|
||||
"Z_TWEEN_SAFE_CLEARANCE: ", p_float_t(Z_TWEEN_SAFE_CLEARANCE, 2),
|
||||
"zoffs: ", p_float_t(zoffs, 2)
|
||||
);
|
||||
|
||||
if (!err_break)
|
||||
current_position.z -= z_measured_min - (Z_TWEEN_SAFE_CLEARANCE + zoffs); // We shouldn't want to subtract the clearance from here right? (Depends if we added it further up)
|
||||
sync_plan_position();
|
||||
#endif
|
||||
|
||||
|
@ -71,11 +71,13 @@ inline void toggle_pins() {
|
||||
else {
|
||||
hal.watchdog_refresh();
|
||||
printPinStateExt(pin, ignore_protection, true, F("Pulsing "));
|
||||
#ifdef __STM32F1__
|
||||
const auto prior_mode = _GET_MODE(i);
|
||||
#else
|
||||
const bool prior_mode = getValidPinMode(pin);
|
||||
#endif
|
||||
const auto prior_mode = (
|
||||
#ifdef __STM32F1__
|
||||
_GET_MODE(i)
|
||||
#else
|
||||
getValidPinMode(pin)
|
||||
#endif
|
||||
);
|
||||
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||
if (pin == TEENSY_E2) {
|
||||
SET_OUTPUT(TEENSY_E2);
|
||||
|
@ -41,7 +41,7 @@ void GcodeSuite::M486() {
|
||||
|
||||
if (parser.seen('T')) {
|
||||
cancelable.reset();
|
||||
cancelable.object_count = parser.intval('T', 1);
|
||||
cancelable.state.object_count = parser.intval('T', 1);
|
||||
}
|
||||
|
||||
if (parser.seenval('S'))
|
||||
|
52
Marlin/src/gcode/feature/macro/M820.cpp
Normal file
52
Marlin/src/gcode/feature/macro/M820.cpp
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2019 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 <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(GCODE_MACROS)
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../queue.h"
|
||||
#include "../../parser.h"
|
||||
|
||||
extern char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1];
|
||||
|
||||
/**
|
||||
* M820: List defined M810 - M819 macros
|
||||
*/
|
||||
void GcodeSuite::M820() {
|
||||
SERIAL_ECHOLNPGM(STR_STORED_MACROS);
|
||||
bool some = false;
|
||||
for (uint8_t i = 0; i < GCODE_MACROS_SLOTS; ++i) {
|
||||
const char *cmd = gcode_macros[i];
|
||||
if (*cmd) {
|
||||
SERIAL_ECHO(F("M81"), i, C(' '));
|
||||
char c;
|
||||
while ((c = *cmd++)) SERIAL_CHAR(c == '\n' ? '|' : c);
|
||||
SERIAL_EOL();
|
||||
some = true;
|
||||
}
|
||||
}
|
||||
if (!some) SERIAL_ECHOLNPGM("None");
|
||||
}
|
||||
|
||||
#endif // GCODE_MACROS
|
@ -75,7 +75,9 @@ void GcodeSuite::G61(int8_t slot/*=-1*/) {
|
||||
|
||||
// No XYZ...E parameters, move to stored position
|
||||
|
||||
float epos = stored_position[slot].e;
|
||||
#if HAS_EXTRUDERS
|
||||
float epos = stored_position[slot].e;
|
||||
#endif
|
||||
if (!parser.seen_axis()) {
|
||||
DEBUG_ECHOLNPGM(STR_RESTORING_POSITION, slot, " (all axes)");
|
||||
// Move to the saved position, all axes except E
|
||||
|
@ -165,7 +165,7 @@ void GcodeSuite::get_destination_from_command() {
|
||||
xyze_bool_t seen{false};
|
||||
|
||||
#if ENABLED(CANCEL_OBJECTS)
|
||||
const bool &skip_move = cancelable.skipping;
|
||||
const bool &skip_move = cancelable.state.skipping;
|
||||
#else
|
||||
constexpr bool skip_move = false;
|
||||
#endif
|
||||
@ -1010,6 +1010,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 810: case 811: case 812: case 813: case 814:
|
||||
case 815: case 816: case 817: case 818: case 819:
|
||||
M810_819(); break; // M810-M819: Define/execute G-code macro
|
||||
case 820: M820(); break; // M820: Report macros to serial output
|
||||
#endif
|
||||
|
||||
#if HAS_BED_PROBE
|
||||
|
@ -128,6 +128,8 @@
|
||||
* M84 - Disable steppers until next move, or use S<seconds> to specify an idle
|
||||
* duration after which steppers should turn off. S0 disables the timeout.
|
||||
* M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||
* M86 - Set / Report Hotend Idle Timeout. (Requires HOTEND_IDLE_TIMEOUT)
|
||||
* M87 - Cancel Hotend Idle Timeout (by setting the timeout period to 0). (Requires HOTEND_IDLE_TIMEOUT)
|
||||
* M92 - Set planner.settings.axis_steps_per_mm for one or more axes. (Requires EDITABLE_STEPS_PER_UNIT)
|
||||
*
|
||||
* M100 - Watch Free Memory (for debugging) (Requires M100_FREE_MEMORY_WATCHER)
|
||||
@ -213,6 +215,8 @@
|
||||
* M281 - Set servo min|max position: "M281 P<index> L<min> U<max>". (Requires EDITABLE_SERVO_ANGLES)
|
||||
* M282 - Detach servo: "M282 P<index>". (Requires SERVO_DETACH_GCODE)
|
||||
* M290 - Babystepping (Requires BABYSTEPPING)
|
||||
* M293 - Babystep Z UP (Requires EP_BABYSTEPPING)
|
||||
* M294 - Babystep Z DOWN (Requires EP_BABYSTEPPING)
|
||||
* M300 - Play beep sound S<frequency Hz> P<duration ms>
|
||||
* M301 - Set PID parameters P I and D. (Requires PIDTEMP)
|
||||
* M302 - Allow cold extrudes, or set the minimum extrude S<temperature>. (Requires PREVENT_COLD_EXTRUSION)
|
||||
@ -246,6 +250,7 @@
|
||||
* M430 - Read the system current, voltage, and power (Requires POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE, or POWER_MONITOR_FIXED_VOLTAGE)
|
||||
* M485 - Send RS485 packets (Requires RS485_SERIAL_PORT)
|
||||
* M486 - Identify and cancel objects. (Requires CANCEL_OBJECTS)
|
||||
* M493 - Get or set input FT Motion / Shaping parameters. (Requires FT_MOTION)
|
||||
* M500 - Store parameters in EEPROM. (Requires EEPROM_SETTINGS)
|
||||
* M501 - Restore parameters from EEPROM. (Requires EEPROM_SETTINGS)
|
||||
* M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! **
|
||||
@ -261,7 +266,7 @@
|
||||
* M554 - Get or set IP gateway. (Requires enabled Ethernet port)
|
||||
* M569 - Enable stealthChop on an axis. (Requires at least one _DRIVER_TYPE to be TMC2130/2160/2208/2209/5130/5160)
|
||||
* M575 - Change the serial baud rate. (Requires BAUD_RATE_GCODE)
|
||||
* M592 - Get or set nonlinear extrusion parameters. (Requires NONLINEAR_EXTRUSION)
|
||||
* M592 - Get or set Nonlinear Extrusion parameters. (Requires NONLINEAR_EXTRUSION)
|
||||
* M593 - Get or set input shaping parameters. (Requires INPUT_SHAPING_[XY])
|
||||
* M600 - Pause for filament change: "M600 X<pos> Y<pos> Z<raise> E<first_retract> L<later_retract>". (Requires ADVANCED_PAUSE_FEATURE)
|
||||
* M603 - Configure filament change: "M603 T<tool> U<unload_length> L<load_length>". (Requires ADVANCED_PAUSE_FEATURE)
|
||||
@ -274,15 +279,17 @@
|
||||
* M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES)
|
||||
* M702 - Unload filament (Requires FILAMENT_LOAD_UNLOAD_GCODES)
|
||||
*
|
||||
* M704 - Preload to MMU (Requires PRUSA_MMU3)
|
||||
* M705 - Eject filament (Requires PRUSA_MMU3)
|
||||
* M706 - Cut filament (Requires PRUSA_MMU3)
|
||||
* M707 - Read from MMU register (Requires PRUSA_MMU3)
|
||||
* M708 - Write to MMU register (Requires PRUSA_MMU3)
|
||||
* M709 - MMU power & reset (Requires PRUSA_MMU3)
|
||||
*** PRUSA_MMU3 ***
|
||||
* M704 - Preload to MMU
|
||||
* M705 - Eject filament
|
||||
* M706 - Cut filament
|
||||
* M707 - Read from MMU register
|
||||
* M708 - Write to MMU register
|
||||
* M709 - MMU power & reset
|
||||
*
|
||||
* M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS)
|
||||
* M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS)
|
||||
* M820 - Report all defined M810-M819 G-code macros (Requires GCODE_MACROS)
|
||||
* M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below)
|
||||
* M852 - Set skew factors: "M852 [I<xy>] [J<xz>] [K<yz>]". (Requires SKEW_CORRECTION_GCODE, plus SKEW_CORRECTION_FOR_Z for IJ)
|
||||
*
|
||||
@ -1194,6 +1201,7 @@ private:
|
||||
|
||||
#if ENABLED(GCODE_MACROS)
|
||||
static void M810_819();
|
||||
static void M820();
|
||||
#endif
|
||||
|
||||
#if HAS_BED_PROBE
|
||||
|
@ -109,7 +109,7 @@ void GcodeSuite::M115() {
|
||||
SERIAL_ECHO(F("CEDE2A2F-"));
|
||||
for (uint8_t i = 1; i <= 6; i++) {
|
||||
print_hex_word(UID[(i % 2) ? i : i - 2]); // 1111-0000-3333-222255554444
|
||||
if (i <= 3) SERIAL_ECHO(C('-'));
|
||||
if (i <= 3) SERIAL_CHAR('-');
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
@ -61,7 +61,9 @@ void GcodeSuite::M360() {
|
||||
PGMSTR(X_STR, "X");
|
||||
PGMSTR(Y_STR, "Y");
|
||||
PGMSTR(Z_STR, "Z");
|
||||
PGMSTR(JERK_STR, "Jerk");
|
||||
#if ANY(CLASSIC_JERK, HAS_LINEAR_E_JERK)
|
||||
PGMSTR(JERK_STR, "Jerk");
|
||||
#endif
|
||||
|
||||
//
|
||||
// Basics and Enabled items
|
||||
|
@ -45,25 +45,24 @@
|
||||
* G5: Cubic B-spline
|
||||
*/
|
||||
void GcodeSuite::G5() {
|
||||
if (MOTION_CONDITIONS) {
|
||||
if (!MOTION_CONDITIONS) return;
|
||||
|
||||
#if ENABLED(CNC_WORKSPACE_PLANES)
|
||||
if (workspace_plane != PLANE_XY) {
|
||||
SERIAL_ERROR_MSG(STR_ERR_BAD_PLANE_MODE);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if ENABLED(CNC_WORKSPACE_PLANES)
|
||||
if (workspace_plane != PLANE_XY) {
|
||||
SERIAL_ERROR_MSG(STR_ERR_BAD_PLANE_MODE);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
get_destination_from_command();
|
||||
get_destination_from_command();
|
||||
|
||||
const xy_pos_t offsets[2] = {
|
||||
{ parser.linearval('I'), parser.linearval('J') },
|
||||
{ parser.linearval('P'), parser.linearval('Q') }
|
||||
};
|
||||
const xy_pos_t offsets[2] = {
|
||||
{ parser.linearval('I'), parser.linearval('J') },
|
||||
{ parser.linearval('P'), parser.linearval('Q') }
|
||||
};
|
||||
|
||||
cubic_b_spline(current_position, destination, offsets, MMS_SCALED(feedrate_mm_s), active_extruder);
|
||||
current_position = destination;
|
||||
}
|
||||
cubic_b_spline(current_position, destination, offsets, MMS_SCALED(feedrate_mm_s), active_extruder);
|
||||
current_position = destination;
|
||||
}
|
||||
|
||||
#endif // BEZIER_CURVE_SUPPORT
|
||||
|
@ -610,23 +610,6 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT)
|
||||
#define HAS_MAX_TC 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675
|
||||
#define HAS_MAX6675 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855
|
||||
#define HAS_MAX31855 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865
|
||||
#define HAS_MAX31865 1
|
||||
#endif
|
||||
|
||||
#if !HAS_MAX_TC
|
||||
#undef THERMOCOUPLE_MAX_ERRORS
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_3 == -4
|
||||
#define TEMP_SENSOR_3_IS_AD8495 1
|
||||
#elif TEMP_SENSOR_3 == -3
|
||||
@ -745,6 +728,23 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT)
|
||||
#define HAS_MAX_TC 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675
|
||||
#define HAS_MAX6675 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855
|
||||
#define HAS_MAX31855 1
|
||||
#endif
|
||||
#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865
|
||||
#define HAS_MAX31865 1
|
||||
#endif
|
||||
|
||||
#if !HAS_MAX_TC
|
||||
#undef THERMOCOUPLE_MAX_ERRORS
|
||||
#endif
|
||||
|
||||
#if TEMP_SENSOR_CHAMBER == -4
|
||||
#define TEMP_SENSOR_CHAMBER_IS_AD8495 1
|
||||
#elif TEMP_SENSOR_CHAMBER == -3
|
||||
@ -1371,7 +1371,7 @@
|
||||
#if MB(MKS_MONSTER8_V1, BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_MINI_E3_V3_0_1, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, BTT_SKR_V3_0, BTT_SKR_V3_0_EZ, AQUILA_V101)
|
||||
|
||||
#define LCD_SERIAL_PORT 1
|
||||
#elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, CREALITY_CR4NTXXC10, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO)
|
||||
#elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, CREALITY_CR4NTXXC10, CREALITY_CR4NS, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO)
|
||||
#define LCD_SERIAL_PORT 2
|
||||
#else
|
||||
#define LCD_SERIAL_PORT 3
|
||||
|
@ -3059,49 +3059,69 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
|
||||
#define INVALID_TMC_UART(ST) (AXIS_HAS_UART(ST) && !(defined(ST##_HARDWARE_SERIAL) || (PINS_EXIST(ST##_SERIAL_RX, ST##_SERIAL_TX))))
|
||||
#if INVALID_TMC_UART(X)
|
||||
#error "TMC2208 or TMC2209 on X requires X_HARDWARE_SERIAL or X_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(X2)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(X2)
|
||||
#error "TMC2208 or TMC2209 on X2 requires X2_HARDWARE_SERIAL or X2_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Y)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Y)
|
||||
#error "TMC2208 or TMC2209 on Y requires Y_HARDWARE_SERIAL or Y_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Y2)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Y2)
|
||||
#error "TMC2208 or TMC2209 on Y2 requires Y2_HARDWARE_SERIAL or Y2_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Z)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Z)
|
||||
#error "TMC2208 or TMC2209 on Z requires Z_HARDWARE_SERIAL or Z_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Z2)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Z2)
|
||||
#error "TMC2208 or TMC2209 on Z2 requires Z2_HARDWARE_SERIAL or Z2_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Z3)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Z3)
|
||||
#error "TMC2208 or TMC2209 on Z3 requires Z3_HARDWARE_SERIAL or Z3_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(Z4)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(Z4)
|
||||
#error "TMC2208 or TMC2209 on Z4 requires Z4_HARDWARE_SERIAL or Z4_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E0)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E0)
|
||||
#error "TMC2208 or TMC2209 on E0 requires E0_HARDWARE_SERIAL or E0_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E1)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E1)
|
||||
#error "TMC2208 or TMC2209 on E1 requires E1_HARDWARE_SERIAL or E1_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E2)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E2)
|
||||
#error "TMC2208 or TMC2209 on E2 requires E2_HARDWARE_SERIAL or E2_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E3)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E3)
|
||||
#error "TMC2208 or TMC2209 on E3 requires E3_HARDWARE_SERIAL or E3_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E4)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E4)
|
||||
#error "TMC2208 or TMC2209 on E4 requires E4_HARDWARE_SERIAL or E4_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E5)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E5)
|
||||
#error "TMC2208 or TMC2209 on E5 requires E5_HARDWARE_SERIAL or E5_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E6)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E6)
|
||||
#error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(E7)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(E7)
|
||||
#error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(I)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(I)
|
||||
#error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(J)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(J)
|
||||
#error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(K)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(K)
|
||||
#error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(U)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(U)
|
||||
#error "TMC2208 or TMC2209 on U requires U_HARDWARE_SERIAL or U_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(V)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(V)
|
||||
#error "TMC2208 or TMC2209 on V requires V_HARDWARE_SERIAL or V_SERIAL_(RX|TX)_PIN."
|
||||
#elif INVALID_TMC_UART(W)
|
||||
#endif
|
||||
#if INVALID_TMC_UART(W)
|
||||
#error "TMC2208 or TMC2209 on W requires W_HARDWARE_SERIAL or W_SERIAL_(RX|TX)_PIN."
|
||||
|
||||
#endif
|
||||
#undef INVALID_TMC_UART
|
||||
|
||||
@ -4309,6 +4329,17 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."
|
||||
#error "SDSUPPORT, BINARY_FILE_TRANSFER, and CUSTOM_FIRMWARE_UPLOAD are required for custom upload."
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Direct Stepping requirements
|
||||
*/
|
||||
#if ENABLED(DIRECT_STEPPING)
|
||||
#if ENABLED(CPU_32_BIT)
|
||||
#error "Direct Stepping is not supported on 32-bit boards."
|
||||
#elif !IS_FULL_CARTESIAN
|
||||
#error "Direct Stepping is incompatible with enabled kinematics."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Input Shaping requirements
|
||||
*/
|
||||
|
@ -42,7 +42,7 @@
|
||||
* version was tagged.
|
||||
*/
|
||||
#ifndef STRING_DISTRIBUTION_DATE
|
||||
#define STRING_DISTRIBUTION_DATE "2024-10-21"
|
||||
#define STRING_DISTRIBUTION_DATE "2024-11-21"
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -729,8 +729,12 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(QUICK_HOME) && (X_SPI_SENSORLESS || Y_SPI_SENSORLESS)
|
||||
#warning "SPI_ENDSTOPS may be unreliable with QUICK_HOME. Adjust SENSORLESS_BACKOFF_MM for better results."
|
||||
#if ENABLED(QUICK_HOME)
|
||||
#if X_SPI_SENSORLESS || Y_SPI_SENSORLESS
|
||||
#warning "If SPI_ENDSTOPS are unreliable with QUICK_HOME try adjusting SENSORLESS_BACKOFF_MM, Travel Acceleration (M204 T), Homing Feedrate (M210 XY), or disable QUICK_HOME."
|
||||
#elif X_SENSORLESS || Y_SENSORLESS
|
||||
#warning "If SENSORLESS_HOMING is unreliable with QUICK_HOME try adjusting SENSORLESS_BACKOFF_MM, Travel Acceleration (M204 T), Homing Feedrate (M210 XY), or disable QUICK_HOME."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HIGHER_CURRENT_HOME_WARNING
|
||||
|
@ -115,9 +115,9 @@ constexpr xyze_float_t max_steps_edit_values =
|
||||
|
||||
constexpr xyz_uint_t min_homing_edit_values = NUM_AXIS_ARRAY_1(MIN_HOMING_EDIT_VALUE);
|
||||
#ifdef DEFAULT_MAX_MULTIPLIER
|
||||
constexpr xyz_uint_t default_homing = HOMING_FEEDRATE_MM_M;
|
||||
constexpr xyz_long_t default_homing = HOMING_FEEDRATE_MM_M;
|
||||
#endif
|
||||
constexpr xyz_uint_t max_homing_edit_values =
|
||||
constexpr xyz_long_t max_homing_edit_values =
|
||||
#ifdef DEFAULT_MAX_MULTIPLIER
|
||||
default_homing * DEFAULT_MAX_MULTIPLIER
|
||||
#else
|
||||
|
@ -2672,7 +2672,7 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
void applyHomingFR() { updateHomingFR(HMI_value.axis, MenuData.Value); }
|
||||
void applyHomingFR() { updateHomingFR(hmiValue.axis, menuData.value); }
|
||||
#if HAS_X_AXIS
|
||||
void setHomingX() { hmiValue.axis = X_AXIS; setIntOnClick(min_homing_edit_values.x, max_homing_edit_values.x, homing_feedrate_mm_m.x, applyHomingFR); }
|
||||
#endif
|
||||
@ -3799,15 +3799,15 @@ void drawMaxAccelMenu() {
|
||||
if (SET_MENU(homingFRMenu, MSG_HOMING_FEEDRATE, 4)) {
|
||||
BACK_ITEM(drawMotionMenu);
|
||||
#if HAS_X_AXIS
|
||||
static uint16_t xhome = static_cast<uint16_t>(homing_feedrate_mm_m.x);
|
||||
uint16_t xhome = static_cast<uint16_t>(homing_feedrate_mm_m.x);
|
||||
EDIT_ITEM(ICON_MaxSpeedJerkX, MSG_HOMING_FEEDRATE_X, onDrawPIntMenu, setHomingX, &xhome);
|
||||
#endif
|
||||
#if HAS_Y_AXIS
|
||||
static uint16_t yhome = static_cast<uint16_t>(homing_feedrate_mm_m.y);
|
||||
uint16_t yhome = static_cast<uint16_t>(homing_feedrate_mm_m.y);
|
||||
EDIT_ITEM(ICON_MaxSpeedJerkY, MSG_HOMING_FEEDRATE_Y, onDrawPIntMenu, setHomingY, &yhome);
|
||||
#endif
|
||||
#if HAS_Z_AXIS
|
||||
static uint16_t zhome = static_cast<uint16_t>(homing_feedrate_mm_m.z);
|
||||
uint16_t zhome = static_cast<uint16_t>(homing_feedrate_mm_m.z);
|
||||
EDIT_ITEM(ICON_MaxSpeedJerkZ, MSG_HOMING_FEEDRATE_Z, onDrawPIntMenu, setHomingZ, &zhome);
|
||||
#endif
|
||||
}
|
||||
|
@ -449,10 +449,10 @@ namespace LanguageNarrow_en {
|
||||
LSTR MSG_A_RETRACT = _UxGT("Retract Accel");
|
||||
LSTR MSG_A_TRAVEL = _UxGT("Travel Accel");
|
||||
LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping");
|
||||
LSTR MSG_SHAPING_ENABLE = _UxGT("Enable @ shaping");
|
||||
LSTR MSG_SHAPING_DISABLE = _UxGT("Disable @ shaping");
|
||||
LSTR MSG_SHAPING_FREQ = _UxGT("@ frequency");
|
||||
LSTR MSG_SHAPING_ZETA = _UxGT("@ damping");
|
||||
LSTR MSG_SHAPING_ENABLE_N = _UxGT("Enable @ shaping");
|
||||
LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disable @ shaping");
|
||||
LSTR MSG_SHAPING_FREQ_N = _UxGT("@ frequency");
|
||||
LSTR MSG_SHAPING_ZETA_N = _UxGT("@ damping");
|
||||
LSTR MSG_SHAPING_A_FREQ = STR_A _UxGT(" frequency"); // ProUI
|
||||
LSTR MSG_SHAPING_B_FREQ = STR_B _UxGT(" frequency"); // ProUI
|
||||
LSTR MSG_SHAPING_C_FREQ = STR_C _UxGT(" frequency"); // ProUI
|
||||
|
@ -424,10 +424,10 @@ namespace LanguageNarrow_it {
|
||||
LSTR MSG_A_RETRACT = _UxGT("A-Ritrazione");
|
||||
LSTR MSG_A_TRAVEL = _UxGT("A-Spostamento");
|
||||
LSTR MSG_INPUT_SHAPING = _UxGT("Input shaping");
|
||||
LSTR MSG_SHAPING_ENABLE = _UxGT("Abilita shaping @");
|
||||
LSTR MSG_SHAPING_DISABLE = _UxGT("Disabil. shaping @");
|
||||
LSTR MSG_SHAPING_FREQ = _UxGT("Frequenza @");
|
||||
LSTR MSG_SHAPING_ZETA = _UxGT("Smorzamento @");
|
||||
LSTR MSG_SHAPING_ENABLE_N = _UxGT("Abilita shaping @");
|
||||
LSTR MSG_SHAPING_DISABLE_N = _UxGT("Disabil. shaping @");
|
||||
LSTR MSG_SHAPING_FREQ_N = _UxGT("Frequenza @");
|
||||
LSTR MSG_SHAPING_ZETA_N = _UxGT("Smorzamento @");
|
||||
LSTR MSG_SHAPING_A_FREQ = _UxGT("Frequenza ") STR_A; // ProUI
|
||||
LSTR MSG_SHAPING_B_FREQ = _UxGT("Frequenza ") STR_B; // ProUI
|
||||
LSTR MSG_SHAPING_C_FREQ = _UxGT("Frequenza ") STR_C; // ProUI
|
||||
|
@ -721,10 +721,10 @@ namespace LanguageNarrow_ru {
|
||||
LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN = _UxGT("Коэфф.кулера");
|
||||
LSTR MSG_MPC_AMBIENT_XFER_COEFF_FAN_E = _UxGT("Коэфф.кулер *");
|
||||
LSTR MSG_INPUT_SHAPING = _UxGT("Input Shaping");
|
||||
LSTR MSG_SHAPING_ENABLE = _UxGT("Включить шейпинг @");
|
||||
LSTR MSG_SHAPING_DISABLE = _UxGT("Выключить шейпинг @");
|
||||
LSTR MSG_SHAPING_FREQ = _UxGT("@ частота");
|
||||
LSTR MSG_SHAPING_ZETA = _UxGT("@ подавление");
|
||||
LSTR MSG_SHAPING_ENABLE_N = _UxGT("Включить шейпинг @");
|
||||
LSTR MSG_SHAPING_DISABLE_N = _UxGT("Выключить шейпинг @");
|
||||
LSTR MSG_SHAPING_FREQ_N = _UxGT("@ частота");
|
||||
LSTR MSG_SHAPING_ZETA_N = _UxGT("@ подавление");
|
||||
LSTR MSG_FILAMENT_EN = _UxGT("Филамент *");
|
||||
LSTR MSG_SEGMENTS_PER_SECOND = _UxGT("Сегментов/сек");
|
||||
LSTR MSG_DRAW_MIN_X = _UxGT("Рисовать мин X");
|
||||
|
@ -392,10 +392,10 @@ namespace LanguageNarrow_sk {
|
||||
LSTR MSG_A_RETRACT = _UxGT("A-retrakt");
|
||||
LSTR MSG_A_TRAVEL = _UxGT("A-prejazd");
|
||||
LSTR MSG_INPUT_SHAPING = _UxGT("Tvarov. vstupu");
|
||||
LSTR MSG_SHAPING_ENABLE = _UxGT("Povol. tvarov. @");
|
||||
LSTR MSG_SHAPING_DISABLE = _UxGT("Zakáz. tvarov. @");
|
||||
LSTR MSG_SHAPING_FREQ = _UxGT("Frekvencia @");
|
||||
LSTR MSG_SHAPING_ZETA = _UxGT("Tlmenie @");
|
||||
LSTR MSG_SHAPING_ENABLE_N = _UxGT("Povol. tvarov. @");
|
||||
LSTR MSG_SHAPING_DISABLE_N = _UxGT("Zakáz. tvarov. @");
|
||||
LSTR MSG_SHAPING_FREQ_N = _UxGT("Frekvencia @");
|
||||
LSTR MSG_SHAPING_ZETA_N = _UxGT("Tlmenie @");
|
||||
LSTR MSG_XY_FREQUENCY_LIMIT = _UxGT("Max. frekvencia");
|
||||
LSTR MSG_XY_FREQUENCY_FEEDRATE = _UxGT("Min. posun");
|
||||
LSTR MSG_STEPS_PER_MM = _UxGT("Kroky/mm");
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user