Skip to content

Commit

Permalink
Merge branch 'bugfix-2.1.x' into bugfix-2.1.x-August4
Browse files Browse the repository at this point in the history
  • Loading branch information
classicrocker883 authored Nov 13, 2024
2 parents ea8f41e + 81bad7b commit 66817df
Show file tree
Hide file tree
Showing 216 changed files with 4,475 additions and 1,394 deletions.
21 changes: 21 additions & 0 deletions .aiderignore
Original file line number Diff line number Diff line change
@@ -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 changes: 3 additions & 0 deletions .github/workflows/ci-build-tests.yml
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@ jobs:
matrix:
test-platform:

# RP2040
- SKR_Pico

# Native
- linux_native
- simulator_linux_release
Expand Down
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -169,3 +169,6 @@ __pycache__
tags
*.logs
*.bak
.aider*
!.aiderignore
.env
46 changes: 25 additions & 21 deletions Marlin/Configuration.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down Expand Up @@ -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
Expand All @@ -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)
Expand Down Expand Up @@ -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 ===========================
//===========================================================================
Expand Down Expand Up @@ -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!
Expand Down Expand Up @@ -3458,6 +3460,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

Expand Down
4 changes: 2 additions & 2 deletions Marlin/Configuration_adv.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion Marlin/Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion Marlin/Version.h
Original file line number Diff line number Diff line change
Expand Up @@ -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-13"

/**
* The protocol for communication to the host. Protocol indicates communication
Expand Down
56 changes: 36 additions & 20 deletions Marlin/src/HAL/AVR/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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)
Expand All @@ -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)
Expand Down Expand Up @@ -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)) {
Expand Down Expand Up @@ -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)
Expand Down Expand Up @@ -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
2 changes: 1 addition & 1 deletion Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
45 changes: 29 additions & 16 deletions Marlin/src/HAL/DUE/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down Expand Up @@ -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;
Expand All @@ -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);
Expand Down
7 changes: 7 additions & 0 deletions Marlin/src/HAL/ESP32/fastio.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down Expand Up @@ -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)
Expand Down
6 changes: 5 additions & 1 deletion Marlin/src/HAL/ESP32/ota.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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>
Expand Down
Loading

0 comments on commit 66817df

Please sign in to comment.