Merge branch 'bugfix-2.1.x' into pr/27735

This commit is contained in:
Scott Lahteine 2025-03-31 22:56:39 -05:00
commit 3219b9ce1f
282 changed files with 7010 additions and 3593 deletions

View file

@ -113,7 +113,7 @@ jobs:
- BTT_GTR_V1_0
- BTT_SKR_PRO
- FLYF407ZG
- FYSETC_S6
- STM32F446VE_fysetc
- LERDGEK
- LERDGEX
- mks_robin_pro2
@ -151,6 +151,9 @@ jobs:
# HC32
- HC32F460C_aquila_101
# GD32F3
- GD32F303RE_creality_mfl
# LPC176x - Lengthy tests
- LPC1768
- LPC1769

View file

@ -17,7 +17,7 @@ help:
@echo "make tests-all-local-docker : Run all tests locally, using docker"
@echo "make unit-test-single-local : Run unit tests for a single config locally"
@echo "make unit-test-single-local-docker : Run unit tests for a single config locally, using docker"
@echo "make unit-test-all-local : Run all code tests locally"
@echo "make unit-test-all-local : Run all code tests locally"
@echo "make unit-test-all-local-docker : Run all code tests locally, using docker"
@echo "make setup-local-docker : Setup local docker using buildx"
@echo ""

View file

@ -129,6 +129,7 @@
// Name displayed in the LCD "Ready" message and Info menu
//#define CUSTOM_MACHINE_NAME "3D Printer"
//#define CONFIGURABLE_MACHINE_NAME // Add G-code M550 to set/report the machine name
// Printer's unique ID, used by some programs to differentiate between machines.
// Choose your own or use a service like https://www.uuidgenerator.net/version4
@ -695,6 +696,7 @@
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define MIN_POWER 0
//#define PID_DEBUG // Print PID debug data to the serial port. Use 'M303 D' to toggle activation.
//#define PID_PARAMS_PER_HOTEND // Use separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with G-code: M301 E[extruder number, 0-2]
@ -1023,9 +1025,6 @@
// Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers).
#define PRINTABLE_RADIUS 140.0 // (mm)
// Maximum reachable area
#define DELTA_MAX_RADIUS 140.0 // (mm)
// Center-to-center distance of the holes in the diagonal push rods.
#define DELTA_DIAGONAL_ROD 250.0 // (mm)
@ -1538,6 +1537,20 @@
#define PROBE_DEPLOY_FEEDRATE (133*60) // (mm/min) Probe deploy speed
#define PROBE_STOW_FEEDRATE (133*60) // (mm/min) Probe stow speed
/**
* Magnetically Mounted Probe with a Servo mechanism
* Probe Deploy and Stow both follow the same basic sequence:
* - Rotate the SERVO to its Deployed angle
* - Perform XYZ moves to deploy or stow the PROBE
* - Rotate the SERVO to its Stowed angle
*/
//#define MAG_MOUNTED_PROBE_SERVO_NR 0 // Servo Number for this probe
#ifdef MAG_MOUNTED_PROBE_SERVO_NR
#define MAG_MOUNTED_PROBE_SERVO_ANGLES { 90, 0 } // Servo Angles for Deployed, Stowed
#define MAG_MOUNTED_PRE_DEPLOY { PROBE_DEPLOY_FEEDRATE, { 15, 160, 30 } } // Safe position for servo activation
#define MAG_MOUNTED_PRE_STOW { PROBE_DEPLOY_FEEDRATE, { 15, 160, 30 } } // Safe position for servo deactivation
#endif
#define MAG_MOUNTED_DEPLOY_1 { PROBE_DEPLOY_FEEDRATE, { 245, 114, 30 } } // Move to side Dock & Attach probe
#define MAG_MOUNTED_DEPLOY_2 { PROBE_DEPLOY_FEEDRATE, { 210, 114, 30 } } // Move probe off dock
#define MAG_MOUNTED_DEPLOY_3 { PROBE_DEPLOY_FEEDRATE, { 0, 0, 0 } } // Extra move if needed
@ -2897,13 +2910,15 @@
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
/**
* ANET and Tronxy 20x4 Controller
* LCD2004 display with 5 analog buttons.
*
* NOTE: Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
* This LCD is known to be susceptible to electrical interference which
* scrambles the display. Press any button to clear it up.
*/
//#define ZONESTAR_LCD
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
@ -3540,22 +3555,26 @@
// :[1,2,3,4,5,6,7,8]
//#define NUM_M106_FANS 1
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
// is too low, you should also increment SOFT_PWM_SCALE.
/**
* Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
* which is not as annoying as with the hardware PWM. On the other hand, if this frequency
* is too low, you should also increment SOFT_PWM_SCALE.
*/
//#define FAN_SOFT_PWM
// Incrementing this by 1 will double the software PWM frequency,
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
// However, control resolution will be halved for each increment;
// at zero value, there are 128 effective control positions.
// :[0,1,2,3,4,5,6,7]
/**
* Incrementing this by 1 will double the software PWM frequency, affecting heaters, and
* the fan if FAN_SOFT_PWM is enabled. However, control resolution will be halved for each
* increment; at zero value, there are 128 effective control positions.
* :[0,1,2,3,4,5,6,7]
*/
#define SOFT_PWM_SCALE 0
// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can
// be used to mitigate the associated resolution loss. If enabled,
// some of the PWM cycles are stretched so on average the desired
// duty cycle is attained.
/**
* If SOFT_PWM_SCALE is set to a value higher than 0, dithering can be used to mitigate the
* associated resolution loss. If enabled, some of the PWM cycles are stretched so on average
* the desired duty cycle is attained.
*/
//#define SOFT_PWM_DITHER
// @section extras
@ -3565,9 +3584,11 @@
// @section lights
// Temperature status LEDs that display the hotend and bed temperature.
// If all hotends, bed temperature, and target temperature are under 54C
// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis)
/**
* Temperature status LEDs that display the hotend and bed temperature.
* If all hotends, bed temperature, and target temperature are under 54C
* the BLUE led is on. Otherwise the RED led is on. (1C hysteresis)
*/
//#define TEMP_STAT_LEDS
// Support for BlinkM/CyzRgb

View file

@ -1419,24 +1419,24 @@
#define MICROSTEP_MODES { 16, 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
* @section stepper motor current
*
* Some boards have a means of setting the stepper motor current via firmware.
* Some boards have a means of setting the stepper motor current via firmware.
*
* The power on motor currents are set by:
* PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2
* known compatible chips: A4982
* DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H
* known compatible chips: AD5206
* DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2
* known compatible chips: MCP4728
* DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, AZTEEG_X5_MINI_WIFI, MIGHTYBOARD_REVE
* known compatible chips: MCP4451, MCP4018
* The power on motor currents are set by:
* PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2
* known compatible chips: A4982
* DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H
* known compatible chips: AD5206
* DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2
* known compatible chips: MCP4728
* DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, AZTEEG_X5_MINI_WIFI, MIGHTYBOARD_REVE
* known compatible chips: MCP4451, MCP4018
*
* Motor currents can also be set by M907 - M910 and by the LCD.
* M907 - applies to all.
* M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H
* M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2
* Motor currents can also be set by M907 - M910 and by the LCD.
* M907 - applies to all.
* M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H
* M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2
*/
//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps
//#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
@ -1619,6 +1619,10 @@
//#define SOUND_MENU_ITEM // Add a mute option to the LCD menu
#define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state
#if ENABLED(U8GLIB_SSD1309)
//#define LCD_DOUBLE_BUFFER // Optimize display updates. Costs ~1K of SRAM.
#endif
#if HAS_WIRED_LCD
//#define DOUBLE_LCD_FRAMERATE // Not recommended for slow boards.
#endif
@ -2227,7 +2231,7 @@
// Developer menu (accessed by touching "About Printer" copyright text)
//#define TOUCH_UI_DEVELOPER_MENU
#endif
#endif // TOUCH_UI_FTDI_EVE
//
// Classic UI Options
@ -2634,19 +2638,23 @@
#define MAX_CMD_SIZE 96
#define BUFSIZE 4
// Transmission to Host Buffer Size
// To save 386 bytes of flash (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0.
// To buffer a simple "ok" you need 4 bytes.
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
/**
* Host Transmit Buffer Size
* - Costs 386 bytes of flash and TX_BUFFER_SIZE+3 bytes of SRAM (if not 0).
* - 4 bytes required to buffer a simple "ok".
* - 32 bytes for ADVANCED_OK (M105).
* - 128 bytes for the optimal speed of 'debug-echo:'
* - Other output doesn't need to be that speedy.
* :[0, 2, 4, 8, 16, 32, 64, 128, 256]
*/
#define TX_BUFFER_SIZE 0
// Host Receive Buffer Size
// Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
// To use flow control, set this buffer size to at least 1024 bytes.
// :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
/**
* Host Receive Buffer Size
* Without XON/XOFF flow control (see SERIAL_XON_XOFF below) 32 bytes should be enough.
* To use flow control, set this buffer size to at least 1024 bytes.
* :[0, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048]
*/
//#define RX_BUFFER_SIZE 1024
#if RX_BUFFER_SIZE >= 1024
@ -2987,6 +2995,8 @@
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
//#define EDITABLE_HOMING_CURRENT // Add a G-code and menu to modify the Homing Current
/**
* Interpolate microsteps to 256
* Override for each driver with <driver>_INTERPOLATE settings below
@ -3913,7 +3923,7 @@
/**
* Extra options for the M114 "Current Position" report
*/
//#define M114_DETAIL // Use 'M114` for details to check planner calculations
//#define M114_DETAIL // Use 'M114 D' for details to check planner calculations
//#define M114_REALTIME // Real current position based on forward kinematics
//#define M114_LEGACY // M114 used to synchronize on every call. Enable if needed.
@ -3960,7 +3970,6 @@
* Spend 28 bytes of SRAM to optimize the G-code parser
*/
#define FASTER_GCODE_PARSER
#if ENABLED(FASTER_GCODE_PARSER)
//#define GCODE_QUOTED_STRINGS // Support for quoted string parameters
#endif

View file

@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
//#define STRING_DISTRIBUTION_DATE "2025-03-10"
//#define STRING_DISTRIBUTION_DATE "2025-04-01"
/**
* The protocol for communication to the host. Protocol indicates communication

View file

@ -55,12 +55,12 @@
#if defined(ARDUINO) && !defined(ARDUINO_ARCH_STM32) && !defined(ARDUINO_ARCH_SAM)
#include "../../inc/MarlinConfigPre.h"
#include "../../../inc/MarlinConfigPre.h"
#if HAS_MARLINUI_U8GLIB
#include "../shared/Marduino.h"
#include "../shared/Delay.h"
#include "../../shared/Marduino.h"
#include "../../shared/Delay.h"
#include <U8glib-HAL.h>

View file

@ -56,16 +56,12 @@
#else
#define G2_PWM_Y 0
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#if HAS_MOTOR_CURRENT_PWM_Z
#define G2_PWM_Z 1
#else
#define G2_PWM_Z 0
#endif
#if HAS_MOTOR_CURRENT_PWM_E
#define G2_PWM_E 1
#else
#define G2_PWM_E 0
#endif
#define G2_PWM_E HAS_MOTOR_CURRENT_PWM_E
#define G2_MASK_X(V) (G2_PWM_X * (V))
#define G2_MASK_Y(V) (G2_PWM_Y * (V))
#define G2_MASK_Z(V) (G2_PWM_Z * (V))
@ -80,17 +76,22 @@ PWM_map ISR_table[NUM_PWMS] = PWM_MAP_INIT;
void Stepper::digipot_init() {
#if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, 0); // init pins
#if G2_PWM_X
OUT_WRITE(MOTOR_CURRENT_PWM_X_PIN, LOW); // init pins
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Y)
OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, 0);
#if G2_PWM_Y
OUT_WRITE(MOTOR_CURRENT_PWM_Y_PIN, LOW);
#endif
#if G2_PWM_Z
OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, 0);
OUT_WRITE(MOTOR_CURRENT_PWM_Z_PIN, LOW);
#endif
#if G2_PWM_E
OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, 0);
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
OUT_WRITE(MOTOR_CURRENT_PWM_E_PIN, LOW);
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E0)
OUT_WRITE(MOTOR_CURRENT_PWM_E0_PIN, LOW);
#endif
#endif
#define WPKEY (0x50574D << 8) // “PWM” in ASCII

View file

@ -0,0 +1,120 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
uint16_t MarlinHAL::adc_result;
#if ENABLED(POSTMORTEM_DEBUGGING)
extern void install_min_serial();
#endif
#if ENABLED(MARLIN_DEV_MODE)
// Dump the clock frequencies of the system, AHB, APB1, APB2, and F_CPU.
static inline void HAL_clock_frequencies_dump() {
auto& rcuInstance = rcu::RCU::get_instance();
uint32_t freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_SYS);
SERIAL_ECHOPGM("\nSYSTEM_CLOCK=", freq);
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_AHB);
SERIAL_ECHOPGM("\nABH_CLOCK=", freq);
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB1);
SERIAL_ECHOPGM("\nAPB1_CLOCK=", freq);
freq = rcuInstance.get_clock_frequency(rcu::Clock_Frequency::CK_APB2);
SERIAL_ECHOPGM("\nAPB2_CLOCK=", freq,
"\nF_CPU=", F_CPU);
// Done
SERIAL_ECHOPGM("\n--\n");
}
#endif // MARLIN_DEV_MODE
// Initializes the Marlin HAL
void MarlinHAL::init() {
constexpr unsigned int cpuFreq = F_CPU;
UNUSED(cpuFreq);
#if PIN_EXISTS(LED)
OUT_WRITE(LED_PIN, LOW);
#endif
SetTimerInterruptPriorities();
// Print clock frequencies to host serial
TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump());
// Register min serial
TERN_(POSTMORTEM_DEBUGGING, install_min_serial());
}
// Returns the reset source based on the flags set in the RCU module
uint8_t MarlinHAL::get_reset_source() {
return
(RCU_I.get_flag(rcu::Status_Flags::FLAG_FWDGTRST)) ? RST_WATCHDOG :
(RCU_I.get_flag(rcu::Status_Flags::FLAG_SWRST)) ? RST_SOFTWARE :
(RCU_I.get_flag(rcu::Status_Flags::FLAG_EPRST)) ? RST_EXTERNAL :
(RCU_I.get_flag(rcu::Status_Flags::FLAG_PORRST)) ? RST_POWER_ON :
(RCU_I.get_flag(rcu::Status_Flags::FLAG_LPRST)) ? RST_BROWN_OUT :
0;
}
// Returns the amount of free memory available in bytes
int MarlinHAL::freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
// Watchdog Timer
#if ENABLED(USE_WATCHDOG)
#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
#include <FWatchdogTimer.h>
FWatchdogTimer& watchdogTimer = FWatchdogTimer::get_instance();
// Initializes the watchdog timer
void MarlinHAL::watchdog_init() {
IF_DISABLED(DISABLE_WATCHDOG_INIT, watchdogTimer.begin(WDT_TIMEOUT_US));
}
// Refreshes the watchdog timer to prevent system reset
void MarlinHAL::watchdog_refresh() {
watchdogTimer.reload();
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Heartbeat indicator
#endif
}
#endif
extern "C" {
extern unsigned int _ebss; // End of bss section
}
// Resets the system to initiate a firmware flash.
WEAK void flashFirmware(const int16_t) {
hal.reboot();
}
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,158 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define CPU_32_BIT
#include "../../core/macros.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "temp_soc.h"
#include "fastio.h"
#include "Servo.h"
#include "../../inc/MarlinConfigPre.h"
#include <stdint.h>
#include <GPIO.hpp>
#include <AFIO.hpp>
// Default graphical display delays
#define CPU_ST7920_DELAY_1 300
#define CPU_ST7920_DELAY_2 40
#define CPU_ST7920_DELAY_3 340
// Serial Ports
#include "MarlinSerial.h"
// Interrupts
#define CRITICAL_SECTION_START() const bool irqon = !__get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (irqon) __enable_irq()
#define cli() __disable_irq()
#define sei() __enable_irq()
// Alias of __bss_end__
#define __bss_end __bss_end__
// Types
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef uint8_t pin_t; // Parity with mfl platform
// Servo
class libServo;
typedef libServo hal_servo_t;
#define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
#define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
// Debugging
#define JTAG_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_DP_ONLY_REMAP)
#define JTAGSWD_DISABLE() AFIO_I.set_remap(gpio::Pin_Remap_Select::SWJ_ALL_DISABLED_REMAP)
#define JTAGSWD_RESET() AFIO_I.set_remap(gpio::Pin_Remap_Select::FULL_SWJ_REMAP)
// ADC
#ifdef ADC_RESOLUTION
#define HAL_ADC_RESOLUTION ADC_RESOLUTION
#else
#define HAL_ADC_RESOLUTION 12
#endif
#define HAL_ADC_VREF_MV 3300
// Disable Marlin's software oversampling.
// The MFL framework uses 16x hardware oversampling by default
#define HAL_ADC_FILTERED
#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);
#define HAL_CAN_SET_PWM_FREQ // This HAL supports PWM Frequency adjustment
extern "C" char* _sbrk(int incr);
extern "C" char* dtostrf(double val, signed char width, unsigned char prec, char* sout);
// MarlinHAL Class
class MarlinHAL {
public:
// 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() { NVIC_SystemReset(); } // restart the firmware from 0x0
// Interrupts
static bool isr_state() { return !__get_PRIMASK(); }
static void isr_on() { sei(); }
static void isr_off() { cli(); }
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() { RCU_I.clear_all_reset_flags(); }
// Free SRAM
static int freeMemory();
// ADC methods
static uint16_t adc_result;
// Called by Temperature::init once at startup
static void adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
// Called by Temperature::init for each sensor at startup
static void adc_enable(const pin_t pin) { pinMode(pin, INPUT); }
// Called from Temperature::isr to start ADC sampling on the given pin
static void adc_start(const pin_t pin) { adc_result = static_cast<uint16_t>(analogRead(pin)); }
// Check if ADC is ready for reading
static bool adc_ready() { return true; }
// Current value of the ADC register
static uint16_t adc_value() { return adc_result; }
// Set the PWM duty cycle for the pin to the given value.
// Optionally invert the duty cycle [default = false]
// Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255U, const bool invert = false);
// Set the frequency of the timer for the given pin.
// All Timer PWM pins run at the same frequency.
static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired);
};

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <SPI.h>
using MarlinSPI = SPIClass;

View file

@ -0,0 +1,101 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#include "MarlinSerial.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
#endif
using namespace arduino;
MarlinSerial& MarlinSerial::get_instance(usart::USART_Base Base, pin_size_t rxPin, pin_size_t txPin) {
UsartSerial& serial = UsartSerial::get_instance(Base, rxPin, txPin);
return *reinterpret_cast<MarlinSerial*>(&serial);
}
#if USING_HW_SERIAL0
MSerialT MSerial0(true, MarlinSerial::get_instance(usart::USART_Base::USART0_BASE, NO_PIN, NO_PIN));
#endif
#if USING_HW_SERIAL1
MSerialT MSerial1(true, MarlinSerial::get_instance(usart::USART_Base::USART1_BASE, NO_PIN, NO_PIN));
#endif
#if USING_HW_SERIAL2
MSerialT MSerial2(true, MarlinSerial::get_instance(usart::USART_Base::USART2_BASE, NO_PIN, NO_PIN));
#endif
#if USING_HW_SERIAL3
MSerialT MSerial3(true, MarlinSerial::get_instance(usart::USART_Base::UART3_BASE, NO_PIN, NO_PIN));
#endif
#if USING_HW_SERIAL4
MSerialT MSerial4(true, MarlinSerial::get_instance(usart::USART_Base::UART4_BASE, NO_PIN, NO_PIN));
#endif
#if ENABLED(EMERGENCY_PARSER)
// This callback needs to access the specific MarlinSerial instance
// We'll use a static pointer to track the current instance
static MarlinSerial* current_serial_instance = nullptr;
static void emergency_callback() {
if (current_serial_instance) {
uint8_t last_data = current_serial_instance->get_last_data();
emergency_parser.update(current_serial_instance->emergency_state, last_data);
}
}
void MarlinSerial::register_emergency_callback(void (*callback)()) {
usart_.register_interrupt_callback(usart::Interrupt_Type::INTR_RBNEIE, callback);
}
#endif
void MarlinSerial::begin(unsigned long baudrate, uint16_t config) {
UsartSerial::begin(baudrate, config);
#if DISABLED(SERIAL_DMA)
#if ENABLED(EMERGENCY_PARSER)
current_serial_instance = this;
register_emergency_callback(emergency_callback);
#endif
#endif
}
void MarlinSerial::updateRxDmaBuffer() {
#if ENABLED(EMERGENCY_PARSER)
// Get the number of bytes available in the receive buffer
size_t available_bytes = usart_.available_for_read(true);
uint8_t data;
// Process only the available data
for (size_t i = 0; i < available_bytes; ++i) {
if (usart_.read_rx_buffer(data)) {
emergency_parser.update(emergency_state, data);
}
}
#endif
// Call the base class implementation to handle any additional updates
UsartSerial::updateRxDmaBuffer();
}
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,75 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
#endif
#include <UsartSerial.hpp>
#include "../../core/serial_hook.h"
#define SERIAL_INDEX_MIN 0
#define SERIAL_INDEX_MAX 4
#include "../shared/serial_ports.h"
#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI)
#define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()
#endif
using namespace arduino;
struct MarlinSerial : public UsartSerial {
static MarlinSerial& get_instance(usart::USART_Base Base, pin_size_t rxPin = NO_PIN, pin_size_t txPin = NO_PIN);
void begin(unsigned long baudrate, uint16_t config);
inline void begin(unsigned long baudrate) { begin(baudrate, SERIAL_8N1); }
void updateRxDmaBuffer();
#if DISABLED(SERIAL_DMA)
FORCE_INLINE static uint8_t buffer_overruns() { return 0; }
#endif
#if ENABLED(EMERGENCY_PARSER)
EmergencyParser::State emergency_state;
// Accessor method to get the last received byte
uint8_t get_last_data() { return usart_.get_last_data(); }
// Register the emergency callback
void register_emergency_callback(void (*callback)());
#endif
protected:
using UsartSerial::UsartSerial;
};
typedef Serial1Class<MarlinSerial> MSerialT;
extern MSerialT MSerial0;
extern MSerialT MSerial1;
extern MSerialT MSerial2;
extern MSerialT MSerial3;
extern MSerialT MSerial4;

View file

@ -0,0 +1,163 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(POSTMORTEM_DEBUGGING)
#include "../shared/MinSerial.h"
// Base addresses for USART peripherals
static constexpr uintptr_t USART_base[] = {
0x40013800, // USART0
0x40004400, // USART1
0x40004800, // USART2
0x40004C00, // UART3
0x40005000 // UART4
};
// Register offsets
static constexpr uint32_t STAT0_OFFSET = 0x00U;
static constexpr uint32_t DATA_OFFSET = 0x04U;
static constexpr uint32_t BAUD_OFFSET = 0x08U;
static constexpr uint32_t CTL0_OFFSET = 0x0CU;
static constexpr uint32_t CTL1_OFFSET = 0x14U;
// Bit positions
static constexpr uint32_t TBE_BIT = 7;
static constexpr uint32_t TEN_BIT = 3;
static constexpr uint32_t UEN_BIT = 13;
// NVIC interrupt numbers for USART
static constexpr int nvicUART[] = { 37, 38, 39, 52, 53 };
// RCU PCLK values for USART
static constexpr rcu::RCU_PCLK clockRegs[] = {
rcu::RCU_PCLK::PCLK_USART0,
rcu::RCU_PCLK::PCLK_USART1,
rcu::RCU_PCLK::PCLK_USART2,
rcu::RCU_PCLK::PCLK_UART3,
rcu::RCU_PCLK::PCLK_UART4
};
// Memory barrier instructions
#define isb() __asm__ __volatile__ ("isb" : : : "memory")
#define dsb() __asm__ __volatile__ ("dsb" : : : "memory")
#define sw_barrier() __asm__ volatile("" : : : "memory")
// Direct register access macros
#define USART_REG(offset) (*(volatile uint32_t*)(USART_base[SERIAL_PORT] + (offset)))
#define USART_STAT0 USART_REG(STAT0_OFFSET)
#define USART_DATA USART_REG(DATA_OFFSET)
#define USART_BAUD USART_REG(BAUD_OFFSET)
#define USART_CTL0 USART_REG(CTL0_OFFSET)
#define USART_CTL1 USART_REG(CTL1_OFFSET)
// Bit manipulation macros
#define READ_BIT(reg, bit) (((reg) >> (bit)) & 1U)
#define SET_BIT(reg, bit) ((reg) |= (1U << (bit)))
#define CLEAR_BIT(reg, bit) ((reg) &= ~(1U << (bit)))
// Initializes the MinSerial interface.
// This function sets up the USART interface for serial communication.
// If the selected serial port is not a hardware port, it disables the severe error reporting feature.
static void MinSerialBegin() {
#if !WITHIN(SERIAL_PORT, 0, 4)
#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
int nvicIndex = nvicUART[SERIAL_PORT];
// NVIC base address for interrupt disable
struct NVICMin {
volatile uint32_t ISER[32];
volatile uint32_t ICER[32];
};
NVICMin *nvicBase = (NVICMin*)0xE000E100;
SBI32(nvicBase->ICER[nvicIndex >> 5], nvicIndex & 0x1F);
// We require memory barriers to properly disable interrupts
// (https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the)
dsb();
isb();
// Get the RCU PCLK for this USART
rcu::RCU_PCLK pclk = clockRegs[SERIAL_PORT];
// Disable then enable usart peripheral clocks
rcu::RCU_DEVICE.set_pclk_enable(pclk, false);
rcu::RCU_DEVICE.set_pclk_enable(pclk, true);
// Save current baudrate
uint32_t baudrate = USART_BAUD;
// Reset USART control registers
USART_CTL0 = 0;
USART_CTL1 = 0; // 1 stop bit
// Restore baudrate
USART_BAUD = baudrate;
// Enable transmitter and USART (8 bits, no parity, 1 stop bit)
SET_BIT(USART_CTL0, TEN_BIT);
SET_BIT(USART_CTL0, UEN_BIT);
#endif
}
// Writes a single character to the serial port.
static void MinSerialWrite(char c) {
#if WITHIN(SERIAL_PORT, 0, 4)
// Wait until transmit buffer is empty
while (!READ_BIT(USART_STAT0, TBE_BIT)) {
hal.watchdog_refresh();
sw_barrier();
}
// Write character to data register
USART_DATA = c;
#endif
}
// Installs the minimum serial interface.
// Sets the HAL_min_serial_init and HAL_min_serial_out function pointers to MinSerialBegin and MinSerialWrite respectively.
void install_min_serial() {
HAL_min_serial_init = &MinSerialBegin;
HAL_min_serial_out = &MinSerialWrite;
}
extern "C" {
// A low-level assembly-based jump handler.
// Unconditionally branches to the CommonHandler_ASM function.
__attribute__((naked, aligned(4))) void JumpHandler_ASM() {
__asm__ __volatile__ ("b CommonHandler_ASM\n");
}
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler();
void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler();
}
#endif // POSTMORTEM_DEBUGGING
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,8 @@
# Generic GD32 HAL based on the MFL Arduino Core
This HAL is eventually intended to act as the generic HAL for all GD32 chips using the MFL library.
Currently it supports:
* GD32F303RET6
Targeting the official [MFL Arduino Core](https://github.com/bnmguy/ArduinoCore_MFL).

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,214 @@
//
// MFL gd32f30x SDCARD using DMA through SDIO in C++
//
// Copyright (C) 2025 B. Mourit <bnmguy@gmail.com>
//
// This software is free software: you can redistribute it and/or modify it under the terms of the
// GNU Lesser General Public License as published by the Free Software Foundation,
// either version 3 of the License, or (at your option) any later version.
//
// This software 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 Lesser General Public License for more details.
//
// You should have received a copy of the GNU Lesser General Public License along with this software.
// If not, see <https://www.gnu.org/licenses/>.
//
#pragma once
#include "../../inc/MarlinConfig.h"
#include "SDIO.hpp"
namespace sdio {
class DMA;
class CardDMA {
public:
static CardDMA& get_instance();
SDIO_Error_Type init();
SDIO_Error_Type card_init();
SDIO_Error_Type begin_startup_procedure();
void begin_shutdown_procedure();
// Configuration
SDIO_Error_Type set_hardware_bus_width(Bus_Width width);
// Main read/write functions for single and multiblock transfers
SDIO_Error_Type read(uint8_t* buf, uint32_t address, uint32_t count);
SDIO_Error_Type write(uint8_t* buf, uint32_t address, uint32_t count);
// DMA transfers
// Other card functions
SDIO_Error_Type erase(uint32_t address_start, uint32_t address_end);
// Interrupt handler
void handle_interrupts();
// Card select
SDIO_Error_Type select_deselect();
SDIO_Error_Type get_card_interface_status(uint32_t* status);
SDIO_Error_Type get_sdcard_status(uint32_t* status);
void check_dma_complete();
SDIO_Error_Type stop_transfer();
Transfer_State get_transfer_state();
uint32_t get_card_capacity() const;
SDIO_Error_Type send_bus_width_command(uint32_t width_value);
SDIO_Error_Type get_card_specific_data(Card_Info* info);
constexpr Block_Size get_data_block_size_index(uint16_t size);
SDIO_Error_Type get_card_state(Card_State* card_state);
SDIO_Error_Type check_sdio_status(Command_Index index = Command_Index::INVALID, bool check_index = false, bool ignore_crc = false);
// DMA configuration
void set_dma_parameters(uint8_t* buf, uint32_t count, bool is_write);
// SDIO configuration
void sdio_configure(const SDIO_Config config) { sdio_.init(config); }
// Varaible stored parameters
SDIO_Error_Type get_scr(uint16_t rca, uint32_t* scr);
SDIO_Error_Type store_cid();
SDIO_Error_Type store_csd();
// Accessor methods
SDIO_Config& get_config() { return config_; }
dma::DMA& get_dma_instance() { return dma_; }
void set_data_end_interrupt() { sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, true); }
void set_sdio_dma_enable(bool enable) { sdio_.set_dma_enable(enable); }
bool get_is_sdio_rx() { return is_rx_; }
void clear_sdio_data_flags() { sdio_.clear_multiple_interrupt_flags(clear_data_flags); }
void clear_sdio_cmd_flags() { sdio_.clear_multiple_interrupt_flags(clear_command_flags); }
void clear_sdio_common_flags() { sdio_.clear_multiple_interrupt_flags(clear_common_flags); }
Operational_State get_state() { return current_state_; }
void set_state(Operational_State state) { current_state_ = state; }
void set_transfer_end(bool value) { transfer_end_ = value; }
void set_transfer_error(SDIO_Error_Type error) { transfer_error_ = error; }
inline SDIO_Error_Type set_desired_clock(uint32_t desired_clock, bool wide_bus, bool low_power) {
sdio_.init({
desired_clock,
Clock_Edge::RISING_EDGE,
wide_bus ? Bus_Width::WIDTH_4BIT : Bus_Width::WIDTH_1BIT,
false,
low_power,
false
});
sync_domains();
desired_clock_ = desired_clock;
return SDIO_Error_Type::OK;
}
private:
CardDMA();
// Prevent copying or assigning
CardDMA(const CardDMA&) = delete;
CardDMA& operator=(const CardDMA&) = delete;
// Helper function
SDIO_Error_Type wait_for_card_ready();
// Member variables
alignas(4) uint32_t sdcard_csd_[4];
alignas(4) uint32_t sdcard_cid_[4];
alignas(4) uint32_t sdcard_scr_[2];
uint32_t desired_clock_;
uint32_t stop_condition_;
uint32_t total_bytes_;
uint32_t count_;
SDIO& sdio_;
SDIO_Config& config_;
const dma::DMA_Base dmaBase_;
const dma::DMA_Channel dmaChannel_;
dma::DMA& dma_;
uint16_t sdcard_rca_;
SDIO_Error_Type transfer_error_;
Interface_Version interface_version_;
Card_Type card_type_;
volatile bool transfer_end_;
volatile bool is_rx_;
volatile bool multiblock_;
volatile Operational_State current_state_;
// Private helper methods
SDIO_Error_Type validate_voltage();
SDIO_Error_Type get_r1_result(Command_Index index);
//SDIO_Error_Type get_r2_r3_result();
SDIO_Error_Type get_r6_result(Command_Index index, uint16_t* rca);
SDIO_Error_Type get_r7_result();
//SDIO_Error_Type get_r1_error_type(uint32_t response);
SDIO_Error_Type get_command_sent_result();
inline void sync_domains() {
delayMicroseconds(8);
}
inline bool validate_transfer_params(uint32_t* buf, uint16_t size) {
if (buf == nullptr) return false;
// Size must be > 0, <= 2048 and power of 2
if ((size == 0U) || (size > 2048U) || (size & (size - 1U))) {
return false;
}
return true;
}
void process_sdsc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) {
info->csd.device_size = (static_cast<uint32_t>(csd_bytes[6] & 0x03U) << 10U) |
(static_cast<uint32_t>(csd_bytes[7]) << 2U) |
(static_cast<uint32_t>((csd_bytes[8] & 0xC0U) >> 6U));
info->csd.device_size_multiplier = static_cast<uint8_t>((csd_bytes[9] & 0x03U) << 1U |
(csd_bytes[10] & 0x80U) >> 7U);
info->block_size = static_cast<uint32_t>(1 << info->csd.read_block_length);
info->capacity = static_cast<uint32_t>((info->csd.device_size + 1U) *
(1U << (info->csd.device_size_multiplier + 2U)) *
info->block_size);
}
void process_sdhc_specific_csd(Card_Info* info, const uint8_t* csd_bytes) {
info->csd.device_size = static_cast<uint32_t>((csd_bytes[7] & 0x3FU) << 16U) |
static_cast<uint32_t>((csd_bytes[8]) << 8U) |
static_cast<uint32_t>(csd_bytes[9]);
info->block_size = BLOCK_SIZE;
info->capacity = static_cast<uint32_t>((info->csd.device_size + 1U) *
BLOCK_SIZE * KILOBYTE);
}
void process_common_csd_tail(Card_Info* info, const uint8_t* csd_bytes) {
info->csd.sector_size = static_cast<uint8_t>(((csd_bytes[9] & 0x3FU) << 1U) |
(csd_bytes[10] & 0x80U) >> 7U);
info->csd.speed_factor = static_cast<uint8_t>((csd_bytes[11] & 0x1CU) >> 2U);
info->csd.write_block_length = static_cast<uint8_t>(((csd_bytes[11] & 0x03U) << 2U) |
((csd_bytes[12] & 0xC0U) >> 6U));
info->csd.checksum = static_cast<uint8_t>((csd_bytes[15] & 0xFEU) >> 1U);
}
inline void disable_all_interrupts() {
sdio_.set_interrupt_enable(Interrupt_Type::DTCRCERRIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::DTTMOUTIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::DTENDIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::STBITEIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::TFHIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::RFHIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::TXUREIE, false);
sdio_.set_interrupt_enable(Interrupt_Type::RXOREIE, false);
}
template <typename CheckFunc>
inline SDIO_Error_Type send_command_and_check(Command_Index command, uint32_t argument,
Command_Response response, Wait_Type type, CheckFunc check_result) {
sdio_.set_command_state_machine(command, argument, response, type);
sync_domains();
sdio_.set_command_state_machine_enable(true);
return check_result();
}
};
} // namespace sdio
extern sdio::CardDMA& CardDMA_I;

View file

@ -0,0 +1,122 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#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.");
// Initialize to the default timer priority. This will be overridden by a call from timers.cpp.
// This allows all timer interrupt priorities to be managed from a single location in the HAL.
static uint32_t servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), 12, 0);
// This must be called after the MFL Servo class has initialized the timer.
// To be safe this is currently called after every call to attach().
static void fixServoTimerInterruptPriority() {
NVIC_SetPriority(getTimerUpIRQ(TIMER_SERVO), servo_interrupt_priority);
}
// Default constructor for libServo class.
// Initializes the servo delay, pause state, and pause value.
// Registers the servo instance in the servos array.
libServo::libServo() : delay(servoDelay[servoCount]),
was_attached_before_pause(false),
value_before_pause(0) {
servos[servoCount++] = this;
}
// Attaches a servo to a specified pin.
int8_t libServo::attach(const int pin) {
if (servoCount >= MAX_SERVOS) return -1;
if (pin > 0) servo_pin = pin;
auto result = mflServo.attach(servo_pin);
fixServoTimerInterruptPriority();
return result;
}
// Attaches a servo to a specified pin with minimum and maximum pulse widths.
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 = mflServo.attach(servo_pin, min, max);
fixServoTimerInterruptPriority();
return result;
}
// Moves the servo to a specified position.
void libServo::move(const int value) {
if (attach(0) >= 0) {
mflServo.write(value);
safe_delay(delay);
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
// Pause the servo by detaching it and storing its current state.
void libServo::pause() {
was_attached_before_pause = mflServo.attached();
if (was_attached_before_pause) {
value_before_pause = mflServo.read();
mflServo.detach();
}
}
// Resume a previously paused servo.
// If the servo was attached before the pause, this function re-attaches
// the servo and moves it to the position it was in before the pause.
void libServo::resume() {
if (was_attached_before_pause) {
attach();
move(value_before_pause);
}
}
// Pause all servos by stopping their timers.
void libServo::pause_all_servos() {
for (auto& servo : servos)
if (servo) servo->pause();
}
// Resume all paused servos by starting their timers.
void libServo::resume_all_servos() {
for (auto& servo : servos)
if (servo) servo->resume();
}
// Set the interrupt priority for the servo.
// @param preemptPriority The preempt priority level.
// @param subPriority The sub priority level.
void libServo::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
servo_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
}
#endif // HAS_SERVOS
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,56 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <Servo.h>
#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() { mflServo.detach(); }
int read() { return mflServo.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 mflServo;
int servoPin = 0;
millis_t delay = 0;
bool was_attached_before_pause;
int value_before_pause;
};

View file

@ -0,0 +1,129 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm / Ryan Power
*
* 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 ARDUINO_ARCH_MFL
#include "../../../inc/MarlinConfig.h"
#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
#include <U8glib-HAL.h>
#include "../../shared/HAL_SPI.h"
#define nop asm volatile ("\tnop\n")
static inline uint8_t swSpiTransfer_mode_0(uint8_t b) {
for (uint8_t i = 0; i < 8; ++i) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
WRITE(DOGLCD_SCK, HIGH);
WRITE(DOGLCD_MOSI, state);
b <<= 1;
WRITE(DOGLCD_SCK, LOW);
}
return b;
}
static inline uint8_t swSpiTransfer_mode_3(uint8_t b) {
for (uint8_t i = 0; i < 8; ++i) {
const uint8_t state = (b & 0x80) ? HIGH : LOW;
WRITE(DOGLCD_SCK, LOW);
WRITE(DOGLCD_MOSI, state);
b <<= 1;
WRITE(DOGLCD_SCK, HIGH);
}
return b;
}
static void u8g_sw_spi_shift_out(uint8_t val) {
#if U8G_SPI_USE_MODE_3
swSpiTransfer_mode_3(val);
#else
swSpiTransfer_mode_0(val);
#endif
}
static void swSpiInit() {
#if PIN_EXISTS(LCD_RESET)
SET_OUTPUT(LCD_RESET_PIN);
#endif
SET_OUTPUT(DOGLCD_A0);
OUT_WRITE(DOGLCD_SCK, LOW);
OUT_WRITE(DOGLCD_MOSI, LOW);
OUT_WRITE(DOGLCD_CS, HIGH);
}
uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
switch (msg) {
case U8G_COM_MSG_INIT:
swSpiInit();
break;
case U8G_COM_MSG_STOP:
break;
case U8G_COM_MSG_RESET:
#if PIN_EXISTS(LCD_RESET)
WRITE(LCD_RESET_PIN, arg_val);
#endif
break;
case U8G_COM_MSG_CHIP_SELECT:
#if U8G_SPI_USE_MODE_3 // This LCD SPI is running mode 3 while SD card is running mode 0
if (arg_val) { // SCK idle state needs to be set to the proper idle state before
// the next chip select goes active
WRITE(DOGLCD_SCK, HIGH); // Set SCK to mode 3 idle state before CS goes active
WRITE(DOGLCD_CS, LOW);
nop; // Hold SCK high for a few ns
nop;
}
else {
WRITE(DOGLCD_CS, HIGH);
WRITE(DOGLCD_SCK, LOW); // Set SCK to mode 0 idle state after CS goes inactive
}
#else
WRITE(DOGLCD_CS, !arg_val);
#endif
break;
case U8G_COM_MSG_WRITE_BYTE:
u8g_sw_spi_shift_out(arg_val);
break;
case U8G_COM_MSG_WRITE_SEQ: {
uint8_t* ptr = (uint8_t*)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_shift_out(*ptr++);
arg_val--;
}
} break;
case U8G_COM_MSG_WRITE_SEQ_P: {
uint8_t* ptr = (uint8_t*)arg_ptr;
while (arg_val > 0) {
u8g_sw_spi_shift_out(u8g_pgm_read(ptr));
ptr++;
arg_val--;
}
} break;
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
WRITE(DOGLCD_A0, arg_val);
break;
}
return 1;
}
#endif // HAS_MARLINUI_U8GLIB && FORCE_SOFT_SPI
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,93 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"
#ifndef MARLIN_EEPROM_SIZE
#error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM."
#endif
size_t PersistentStore::capacity() {
return MARLIN_EEPROM_SIZE - eeprom_exclude_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)REAL_EEPROM_ADDR(pos);
// EPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
if (++written & 0x7F) delay(4); else safe_delay(4);
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 {
const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos));
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // IIC_BL24CXX_EEPROM
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,54 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* Platform-independent Arduino functions for I2C EEPROM.
* Enable USE_SHARED_EEPROM if not supplied by the framework.
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#if ENABLED(IIC_BL24CXX_EEPROM)
#include "../../libs/BL24CXX.h"
#include "../shared/eeprom_if.h"
void eeprom_init() {
BL24CXX::init();
}
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
const unsigned eeprom_address = (unsigned)pos;
return BL24CXX::writeOneByte(eeprom_address, value);
}
uint8_t eeprom_read_byte(uint8_t *pos) {
const unsigned eeprom_address = (unsigned)pos;
return BL24CXX::readOneByte(eeprom_address);
}
#endif // IIC_BL24CXX_EEPROM
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,96 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#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 - eeprom_exclude_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)REAL_EEPROM_ADDR(pos);
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
// Avoid triggering watchdog during long EEPROM writes
if (++written & 0x7F)
delay(2);
else
safe_delay(2);
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 {
const uint8_t c = eeprom_read_byte((uint8_t*)REAL_EEPROM_ADDR(pos));
if (writing)
*value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // USE_WIRED_EEPROM
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,61 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <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(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_(USE_Z_MIN, _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, _ATTACH(Z_MIN_PROBE_PIN));
TERN_(USE_CALIBRATION, _ATTACH(CALIBRATION_PIN));
TERN_(USE_I_MAX, _ATTACH(I_MAX_PIN));
TERN_(USE_I_MIN, _ATTACH(I_MIN_PIN));
TERN_(USE_J_MAX, _ATTACH(J_MAX_PIN));
TERN_(USE_J_MIN, _ATTACH(J_MIN_PIN));
TERN_(USE_K_MAX, _ATTACH(K_MAX_PIN));
TERN_(USE_K_MIN, _ATTACH(K_MIN_PIN));
TERN_(USE_U_MAX, _ATTACH(U_MAX_PIN));
TERN_(USE_U_MIN, _ATTACH(U_MIN_PIN));
TERN_(USE_V_MAX, _ATTACH(V_MAX_PIN));
TERN_(USE_V_MIN, _ATTACH(V_MIN_PIN));
TERN_(USE_W_MAX, _ATTACH(W_MAX_PIN));
TERN_(USE_W_MIN, _ATTACH(W_MIN_PIN));
}

View file

@ -0,0 +1,97 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#include <PinOpsMap.hpp>
#include <PinOps.hpp>
#include "timers.h"
static uint16_t timer_frequency[TIMER_COUNT];
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) {
// Calculate duty cycle based on inversion flag
const uint16_t duty = invert ? scale - value : value;
// Check if the pin supports PWM
if (PWM_PIN(pin)) {
// Get the timer peripheral base associated with the pin
const auto timer_base = getPinOpsPeripheralBase<TIMERPinOps, timer::TIMER_Base>(TIMER_PinOps, static_cast<pin_size_t>(pin));
// Initialize the timer instance
auto& TimerInstance = GeneralTimer::get_instance(timer_base);
// Get channel and previous channel mode
const auto channel = getPackedPinChannel(getPackedPinOps(TIMER_PinOps, static_cast<pin_size_t>(pin)));
const InputOutputMode previous = TimerInstance.getChannelMode(channel);
if (timer_frequency[static_cast<size_t>(timer_base)] == 0) {
set_pwm_frequency(pin, PWM_FREQUENCY);
}
// Set the PWM duty cycle
TimerInstance.setCaptureCompare(channel, duty, CCFormat::B8);
// Configure pin as PWM output
pinOpsPinout(TIMER_PinOps, static_cast<pin_size_t>(pin));
// Set channel mode if not already set and start timer
if (previous != InputOutputMode::PWM0) {
TimerInstance.setChannelMode(channel, InputOutputMode::PWM0, static_cast<pin_size_t>(pin));
TimerInstance.start();
}
} else {
pinMode(pin, OUTPUT);
digitalWrite(pin, duty < scale / 2 ? LOW : HIGH);
}
}
void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) {
// Check if the pin supports PWM
if (!PWM_PIN(pin)) return;
// Get the timer peripheral base associated with the pin
const auto timer_base = getPinOpsPeripheralBase<TIMERPinOps, timer::TIMER_Base>(TIMER_PinOps, static_cast<pin_size_t>(pin));
// Guard against modifying protected timers
#ifdef STEP_TIMER
if (timer_base == static_cast<timer::TIMER_Base>(STEP_TIMER)) return;
#endif
#ifdef TEMP_TIMER
if (timer_base == static_cast<timer::TIMER_Base>(TEMP_TIMER)) return;
#endif
#if defined(PULSE_TIMER) && MF_TIMER_PULSE != MF_TIMER_STEP
if (timer_base == static_cast<timer::TIMER_Base>(PULSE_TIMER)) return;
#endif
// Initialize the timer instance
auto& TimerInstance = GeneralTimer::get_instance(timer_base);
TimerInstance.setRolloverValue(f_desired, TimerFormat::HERTZ);
timer_frequency[timer_base_to_index(timer_base)] = f_desired;
}
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,82 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Fast I/O interfaces for GD32F303RE
#include <GPIO.hpp>
#include <PinOps.hpp>
#include <PinOpsMap.hpp>
static inline void fast_write_pin_wrapper(pin_size_t IO, bool V) {
if (V) gpio::fast_set_pin(getPortFromPin(IO), getPinInPort(IO));
else gpio::fast_clear_pin(getPortFromPin(IO), getPinInPort(IO));
}
static inline bool fast_read_pin_wrapper(pin_size_t IO) {
return gpio::fast_read_pin(getPortFromPin(IO), getPinInPort(IO));
}
static inline void fast_toggle_pin_wrapper(pin_size_t IO) {
gpio::fast_toggle_pin(getPortFromPin(IO), getPinInPort(IO));
}
// ------------------------
// Defines
// ------------------------
#ifndef PWM
#define PWM OUTPUT
#endif
#define _WRITE(IO, V) fast_write_pin_wrapper(IO, V)
#define _READ(IO) fast_read_pin_wrapper(IO)
#define _TOGGLE(IO) fast_toggle_pin_wrapper(IO)
#define _GET_MODE(IO)
#define _SET_MODE(IO, M) pinMode((IO), (M))
#define _SET_OUTPUT(IO) pinMode((IO), OUTPUT)
#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)
#define SET_INPUT_PULLUP(IO) _SET_MODE((IO), INPUT_PULLUP)
#define SET_INPUT_PULLDOWN(IO) _SET_MODE((IO), INPUT_PULLDOWN)
#define SET_OUTPUT(IO) OUT_WRITE((IO), LOW)
#define SET_OUTPUT_OD(IO) OUT_WRITE_OD((IO), LOW)
#define SET_PWM(IO) _SET_MODE((IO), PWM)
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) isPinInPinOps(TIMER_PinOps, P)
#define NO_COMPILE_TIME_PWM
// Wrappers for digitalRead and digitalWrite
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO, V) digitalWrite((IO), (V))

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#if ALL(HAS_MARLINUI_U8GLIB, FORCE_SOFT_SPI)
#define U8G_SW_SPI_MFL 1
#endif

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#if ALL(HAS_MEDIA, USBD_USE_CDC_MSC)
#define HAS_SD_HOST_DRIVE 1
#endif

View file

@ -0,0 +1,29 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// If no real or emulated EEPROM selected, fall back to SD emulation
#if USE_FALLBACK_EEPROM
#define SDCARD_EEPROM_EMULATION
#elif ANY(I2C_EEPROM, SPI_EEPROM)
#define USE_SHARED_EEPROM 1
#endif

View file

@ -0,0 +1,22 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once

View file

@ -0,0 +1,97 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// Test MFL GD32 specific configuration values for errors at compile-time.
#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA
#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(FLASH_EEPROM_LEVELING)
#error "FLASH_EEPROM_LEVELING is not supported on GD32."
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
#error "SERIAL_STATS_MAX_RX_QUEUED is not supported on GD32."
#elif ENABLED(SERIAL_STATS_DROPPED_RX)
#error "SERIAL_STATS_DROPPED_RX is not supported on GD32."
#endif
#if TEMP_SENSOR_SOC && defined(ATEMP) && TEMP_SOC_PIN != ATEMP
#error "TEMP_SENSOR_SOC requires 'TEMP_SOC_PIN ATEMP' on GD32"
#endif
// Check for common serial pin conflicts
#define _CHECK_SERIAL_PIN(N) (( \
BTN_EN1 == N || BTN_EN2 == N || DOGLCD_CS == N || HEATER_BED_PIN == N || FAN0_PIN == N || \
SDIO_D2_PIN == N || SDIO_D3_PIN == N || SDIO_CK_PIN == N || SDIO_CMD_PIN == N || \
Y_STEP_PIN == N || Y_ENABLE_PIN == N || E0_ENABLE_PIN == N || POWER_LOSS_PIN == N \
))
#define CHECK_SERIAL_PIN(T, N) defined(UART##N##_##T##_PIN) && _CHECK_SERIAL_PIN(UART##N##_##T##_PIN)
#if SERIAL_IN_USE(0)
#if CHECK_SERIAL_PIN(TX, 0)
#error "Serial Port 0 TX IO pins conflict with another pin on the board."
#endif
#if CHECK_SERIAL_PIN(RX, 0)
#error "Serial Port 0 RX IO pins conflict with another pin on the board."
#endif
#endif
#if SERIAL_IN_USE(1)
#if CHECK_SERIAL_PIN(TX, 1)
#error "Serial Port 1 TX IO pins conflict with another pin on the board."
#endif
#if CHECK_SERIAL_PIN(RX, 1)
#error "Serial Port 1 RX IO pins conflict with another pin on the board."
#endif
#endif
#if SERIAL_IN_USE(2)
#if CHECK_SERIAL_PIN(TX, 2)
#error "Serial Port 2 TX IO pins conflict with another pin on the board."
#endif
#if CHECK_SERIAL_PIN(RX, 2)
#error "Serial Port 2 RX IO pins conflict with another pin on the board."
#endif
#endif
#if SERIAL_IN_USE(3)
#if CHECK_SERIAL_PIN(TX, 3)
#error "Serial Port 3 TX IO pins conflict with another pin on the board."
#endif
#if CHECK_SERIAL_PIN(RX, 3)
#error "Serial Port 3 RX IO pins conflict with another pin on the board."
#endif
#endif
#if SERIAL_IN_USE(4)
#if CHECK_SERIAL_PIN(TX, 4)
#error "Serial Port 4 TX IO pins conflict with another pin on the board."
#endif
#if CHECK_SERIAL_PIN(RX, 4)
#error "Serial Port 4 RX IO pins conflict with another pin on the board."
#endif
#endif
#undef CHECK_SERIAL_PIN
#undef _CHECK_SERIAL_PIN

View file

@ -0,0 +1,102 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Pins Debugging for GD32
*
* - 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 <Arduino.h>
#include <PinOps.hpp>
#include <Analog.h>
#ifndef TOTAL_PIN_COUNT
#error "Expected TOTAL_PIN_COUNT not found."
#endif
#define NUM_DIGITAL_PINS TOTAL_PIN_COUNT
#define NUMBER_PINS_TOTAL TOTAL_PIN_COUNT
#define getPinByIndex(x) pin_t(pin_array[x].pin)
#define isValidPin(P) WITHIN(P, 0, (NUM_DIGITAL_PINS - 1))
#define digitalRead_mod(P) extDigitalRead(P)
#define printPinNumber(P) do { sprintf_P(buffer, PSTR("%3hd "), pin_t(P)); SERIAL_ECHO(buffer); } while (0)
#define printPinAnalog(P) do { sprintf_P(buffer, PSTR(" (A%2d) "), pin_t(getAdcChannelFromPin(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
#ifndef M43_NEVER_TOUCH
#define M43_NEVER_TOUCH(x) WITHIN(x, 9, 10) // SERIAL pins: PA9(TX) PA10(RX)
#endif
bool isAnalogPin(const pin_t pin) {
if (!isValidPin(pin)) return false;
if (getAdcChannel(pin) != adc::ADC_Channel::INVALID) {
auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value();
return instance.get_pin_mode(getPinInPort(pin)) == gpio::Pin_Mode::ANALOG && !M43_NEVER_TOUCH(pin);
}
return false;
}
bool getValidPinMode(const pin_t pin) {
if (!isValidPin(pin)) return false;
auto& instance = gpio::GPIO::get_instance(getPortFromPin(pin)).value();
gpio::Pin_Mode mode = instance.get_pin_mode(getPinInPort(pin));
return mode != gpio::Pin_Mode::ANALOG && mode != gpio::Pin_Mode::INPUT_FLOATING &&
mode != gpio::Pin_Mode::INPUT_PULLUP && mode != gpio::Pin_Mode::INPUT_PULLDOWN;
}
bool getPinIsDigitalByIndex(const int16_t index) {
const pin_t pin = getPinByIndex(index);
return (!isAnalogPin(pin));
}
int8_t digitalPinToAnalogIndex(const pin_t pin) {
if (!isValidPin(pin) || !isAnalogPin(pin)) return -1;
return pin; // Analog and digital pin indexes are shared
}
bool pwm_status(const pin_t pin) { return false; }
void printPinPWM(const pin_t pin) { /* TODO */ }
void printPinPort(const pin_t pin) { /* TODO */ }

View file

@ -0,0 +1,233 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#if ENABLED(ONBOARD_SDIO)
#include <PinOpsMap.hpp>
#include <PinOps.hpp>
#include "SDCard.h"
#include "sdio.h"
using namespace sdio;
#define TARGET_CLOCK 6000000U
#define BLOCK_SIZE 512U
#define CARD_TIMEOUT 500 // ms
#define READ_RETRIES 3U
inline constexpr uint32_t TARGET_SDIO_CLOCK = TARGET_CLOCK;
inline constexpr uint32_t SDIO_BLOCK_SIZE = BLOCK_SIZE;
inline constexpr uint32_t SD_TIMEOUT = CARD_TIMEOUT;
inline constexpr uint8_t SDIO_READ_RETRIES = READ_RETRIES;
Card_State cardState = Card_State::READY;
bool SDIO_SetBusWidth(Bus_Width width) {
return (CardDMA_I.set_hardware_bus_width(width) == SDIO_Error_Type::OK);
}
void mfl_sdio_init() {
pinOpsPinout(SD_CMD_PinOps, static_cast<pin_size_t>(SDIO_CMD_PIN));
pinOpsPinout(SD_CK_PinOps, static_cast<pin_size_t>(SDIO_CK_PIN));
pinOpsPinout(SD_DATA0_PinOps, static_cast<pin_size_t>(SDIO_D0_PIN));
pinOpsPinout(SD_DATA1_PinOps, static_cast<pin_size_t>(SDIO_D1_PIN));
pinOpsPinout(SD_DATA2_PinOps, static_cast<pin_size_t>(SDIO_D2_PIN));
pinOpsPinout(SD_DATA3_PinOps, static_cast<pin_size_t>(SDIO_D3_PIN));
NVIC_EnableIRQ(DMA1_Channel3_4_IRQn);
NVIC_EnableIRQ(SDIO_IRQn);
}
bool SDIO_Init() {
SDIO_Error_Type result = SDIO_Error_Type::OK;
uint8_t retryCount = SDIO_READ_RETRIES;
mfl_sdio_init();
uint8_t retries = retryCount;
for (;;) {
hal.watchdog_refresh();
result = CardDMA_I.init();
if (result == SDIO_Error_Type::OK) break;
if (!--retries) return false;
}
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, false);
retries = retryCount;
for (;;) {
hal.watchdog_refresh();
if (SDIO_SetBusWidth(Bus_Width::WIDTH_4BIT)) break;
if (!--retries) break;
}
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, true, true);
// Fallback
if (!retries) {
mfl_sdio_init();
retries = retryCount;
for (;;) {
hal.watchdog_refresh();
result = CardDMA_I.init();
if (result == SDIO_Error_Type::OK) break;
if (!--retries) return false;
}
CardDMA_I.set_desired_clock(TARGET_SDIO_CLOCK, false, true);
}
return true;
}
static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t* src, uint8_t* dst) {
hal.watchdog_refresh();
SDIO_Error_Type result = SDIO_Error_Type::OK;
// Write
if (src) {
result = CardDMA_I.write(reinterpret_cast<uint8_t*>(const_cast<uint8_t*>(src)), block, 1);
}
// Read
else {
result = CardDMA_I.read(dst, block, 1);
}
if (result != SDIO_Error_Type::OK) {
return false;
}
millis_t timeout = millis() + SD_TIMEOUT;
while (CardDMA_I.get_state() != sdio::Operational_State::READY) {
if (ELAPSED(millis(), timeout)) {
return false;
}
}
CardDMA_I.check_dma_complete();
timeout = millis() + SD_TIMEOUT;
do {
result = CardDMA_I.get_card_state(&cardState);
if (ELAPSED(millis(), timeout)) {
return false;
}
} while (result == SDIO_Error_Type::OK && cardState != sdio::Card_State::TRANSFER);
return true;
}
bool SDIO_ReadBlock(uint32_t block, uint8_t* dst) {
// Check if the address is aligned to 4 bytes
if (reinterpret_cast<uint32_t>(dst) & 0x03) {
return false;
}
uint8_t retries = SDIO_READ_RETRIES;
while (retries--) {
if (SDIO_ReadWriteBlock_DMA(block, nullptr, dst)) {
return true;
}
}
return false;
}
bool SDIO_WriteBlock(uint32_t block, const uint8_t* src) {
// Check if the address is aligned to 4 bytes
if (reinterpret_cast<uint32_t>(src) & 0x03) {
return false;
}
uint8_t retries = SDIO_READ_RETRIES;
while (retries--) {
if (SDIO_ReadWriteBlock_DMA(block, src, nullptr)) {
return true;
delay(10);
}
}
return false;
}
bool SDIO_IsReady() {
return (CardDMA_I.get_state() == sdio::Operational_State::READY);
}
uint32_t SDIO_GetCardSize() {
return CardDMA_I.get_card_capacity();
}
// DMA interrupt handler
void DMA1_IRQHandler() {
auto& dma_instance = CardDMA_I.get_dma_instance();
bool is_receive = CardDMA_I.get_is_sdio_rx();
// Check for Transfer Complete Interrupt
if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF)) {
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false);
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false);
dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_FTFIF);
if (is_receive) {
CardDMA_I.set_sdio_dma_enable(false);
CardDMA_I.clear_sdio_data_flags();
CardDMA_I.set_state(sdio::Operational_State::READY);
} else {
CardDMA_I.set_data_end_interrupt();
}
// Signal that transfer is complete
CardDMA_I.set_transfer_end(true);
}
else if (dma_instance.get_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_ERRIF)) {
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_HTFIE, false);
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_ERRIE, false);
dma_instance.set_interrupt_enable(dma::Interrupt_Type::INTR_FTFIE, false);
// Clear all flags
dma_instance.clear_interrupt_flag(dma::Interrupt_Flags::INTR_FLAG_GIF);
// Signal that an error occurred
CardDMA_I.set_transfer_error(SDIO_Error_Type::ERROR);
CardDMA_I.set_state(sdio::Operational_State::READY);
}
}
extern "C" {
void SDIO_IRQHandler(void) {
CardDMA_I.handle_interrupts();
}
void DMA1_Channel3_4_IRQHandler(void) {
DMA1_IRQHandler();
}
} // extern "C"
#endif // ONBOARD_SDIO
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,36 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <SDIO.hpp>
#include <DMA.hpp>
#define SDIO_D0_PIN PC8
#define SDIO_D1_PIN PC9
#define SDIO_D2_PIN PC10
#define SDIO_D3_PIN PC11
#define SDIO_CK_PIN PC12
#define SDIO_CMD_PIN PD2
void sdio_mfl_init();
bool SDIO_SetBusWidth(sdio::Bus_Width width);
void DMA1_IRQHandler(dma::DMA_Channel channel);

View file

@ -0,0 +1,32 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#pragma once
// Define SPI Pins: SCK, MISO, MOSI
#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

View file

@ -0,0 +1,29 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define TS_TYPICAL_V 1.405
#define TS_TYPICAL_TEMP 25
#define TS_TYPICAL_SLOPE 4.5
// TODO: Implement voltage scaling (calibrated Vrefint) and ADC resolution scaling (when applicable)
#define TEMP_SOC_SENSOR(RAW) ((TS_TYPICAL_V - (RAW) / float(OVERSAMPLENR) / float(HAL_ADC_RANGE) * (float(ADC_VREF_MV) / 1000)) / ((TS_TYPICAL_SLOPE) / 1000) + TS_TYPICAL_TEMP)

View file

@ -0,0 +1,233 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef ARDUINO_ARCH_MFL
#include "../../inc/MarlinConfig.h"
#include "timers.h"
// ------------------------
// Local defines
// ------------------------
#define SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight bit timing to communicate reliably with TMC drivers
#define SERVO_TIMER_IRQ_PRIORITY_DEFAULT 1 // Requires tight PWM timing to control a BLTouch reliably
#define STEP_TIMER_IRQ_PRIORITY_DEFAULT 2
#define TEMP_TIMER_IRQ_PRIORITY_DEFAULT 14 // Low priority avoids interference with other hardware and timers
#ifndef TIMER_IRQ_PRIORITY
#define TIMER_IRQ_PRIORITY 12
#endif
#ifndef STEP_TIMER_IRQ_PRIORITY
#define STEP_TIMER_IRQ_PRIORITY STEP_TIMER_IRQ_PRIORITY_DEFAULT
#endif
#ifndef TEMP_TIMER_IRQ_PRIORITY
#define TEMP_TIMER_IRQ_PRIORITY TEMP_TIMER_IRQ_PRIORITY_DEFAULT
#endif
#if HAS_TMC_SW_SERIAL
#include <SoftwareSerial.h>
#ifndef SWSERIAL_TIMER_IRQ_PRIORITY
#define SWSERIAL_TIMER_IRQ_PRIORITY SWSERIAL_TIMER_IRQ_PRIORITY_DEFAULT
#endif
#endif
#if HAS_SERVOS
#include "Servo.h"
#ifndef SERVO_TIMER_IRQ_PRIORITY
#define SERVO_TIMER_IRQ_PRIORITY SERVO_TIMER_IRQ_PRIORITY_DEFAULT
#endif
#endif
#if ENABLED(SPEAKER)
// The MFL framework default timer priority is 12. The TEMP timer must have lower priority
// than this due to the long running temperature ISR, and STEP timer should higher priority.
#if !(TIMER_IRQ_PRIORITY > STEP_TIMER_IRQ_PRIORITY && TIMER_IRQ_PRIORITY < TEMP_TIMER_IRQ_PRIORITY)
#error "Default timer interrupt priority is unspecified or set to a value which may degrade performance."
#endif
#endif
#ifndef HAL_TIMER_RATE
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
#ifndef STEP_TIMER
#define STEP_TIMER MF_TIMER_STEP
#endif
#ifndef TEMP_TIMER
#define TEMP_TIMER MF_TIMER_TEMP
#endif
GeneralTimer& Step_Timer = GeneralTimer::get_instance(static_cast<timer::TIMER_Base>(STEP_TIMER));
GeneralTimer& Temp_Timer = GeneralTimer::get_instance(static_cast<timer::TIMER_Base>(TEMP_TIMER));
bool is_step_timer_initialized = false;
bool is_temp_timer_initialized = false;
// ------------------------
// Public functions
// ------------------------
// Retrieves the clock frequency of the stepper timer
uint32_t GetStepperTimerClkFreq() {
return Step_Timer.getTimerClockFrequency();
}
/**
* @brief Starts a hardware timer
*
* If the timer is not already initialized, this function will initialize it with the given frequency.
* The timer is started immediately after initialization
*
* @param timer The timer base index to start
* @param frequency The frequency at which the timer should run
* @return None
*/
void HAL_timer_start(const uint8_t timer_number, const uint32_t frequency) {
if (HAL_timer_initialized(timer_number) || (timer_number != MF_TIMER_STEP && timer_number != MF_TIMER_TEMP))
return;
const bool is_step = (timer_number == MF_TIMER_STEP);
const uint8_t priority = is_step ?
static_cast<uint8_t>(STEP_TIMER_IRQ_PRIORITY) :
static_cast<uint8_t>(TEMP_TIMER_IRQ_PRIORITY);
// Get the reference of the timer instance
GeneralTimer& timer = is_step ? Step_Timer : Temp_Timer;
if (is_step) {
timer.setPrescaler(STEPPER_TIMER_PRESCALE);
timer.setRolloverValue(_MIN(static_cast<hal_timer_t>(HAL_TIMER_TYPE_MAX),
(HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)),
TimerFormat::TICK);
is_step_timer_initialized = true;
}
else {
timer.setRolloverValue(frequency, TimerFormat::HERTZ);
is_temp_timer_initialized = true;
}
timer.setAutoReloadEnable(false);
timer.setInterruptPriority(priority, 0U);
HAL_timer_enable_interrupt(timer_number);
timer.start();
}
/**
* @brief Enables the interrupt for the specified timer
*
* @param handle The timer handle for which to enable the interrupt
* @return None
*/
void HAL_timer_enable_interrupt(const uint8_t timer_number) {
if (!HAL_timer_initialized(timer_number)) return;
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
if (timer_number == MF_TIMER_STEP && !timer.hasInterrupt())
timer.attachInterrupt(Step_Handler);
else if (timer_number == MF_TIMER_TEMP && !timer.hasInterrupt())
timer.attachInterrupt(Temp_Handler);
}
/**
* @brief Disables the interrupt for the specified timer
*
* @param handle The timer handle for which to disable the interrupt
* @return None
*/
void HAL_timer_disable_interrupt(const uint8_t timer_number) {
if (!HAL_timer_initialized(timer_number)) return;
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
timer.detachInterrupt();
}
/**
* @brief Checks if the interrupt is enabled for the specified timer
*
* @param handle The timer handle to check
* @return True if the interrupt is enabled, false otherwise
*/
bool HAL_timer_interrupt_enabled(const uint8_t timer_number) {
if (!HAL_timer_initialized(timer_number)) return false;
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
? timer.hasInterrupt()
: false;
}
// Sets the interrupt priorities for timers used by TMC SW serial and servos.
void SetTimerInterruptPriorities() {
TERN_(HAS_TMC_SW_SERIAL, SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIORITY, 0));
TERN_(HAS_SERVOS, libServo::setInterruptPriority(SERVO_TIMER_IRQ_PRIORITY, 0));
}
// ------------------------
// Detect timer conflicts
// ------------------------
TERN_(SPEAKER, static constexpr timer::TIMER_Base timer_tone[] = {static_cast<timer::TIMER_Base>(TIMER_TONE)});
TERN_(HAS_SERVOS, static constexpr timer::TIMER_Base timer_servo[] = {static_cast<timer::TIMER_Base>(TIMER_SERVO)});
enum TimerPurpose {
PURPOSE_TONE,
PURPOSE_SERVO,
PURPOSE_STEP,
PURPOSE_TEMP
};
// List of timers to check for conflicts
// Includes the timer purpose to ease debugging when evaluating at build-time
// This cannot yet account for timers used for PWM output, such as for fans
static constexpr struct { TimerPurpose p; int t; } timers_in_use[] = {
#if ENABLED(SPEAKER)
{ PURPOSE_TONE, timer_base_to_index(timer_tone[0]) }, // Set in variant.h
#endif
#if HAS_SERVOS
{ PURPOSE_SERVO, timer_base_to_index(timer_servo[0]) }, // Set in variant.h
#endif
{ PURPOSE_STEP, MF_TIMER_STEP },
{ PURPOSE_TEMP, MF_TIMER_TEMP },
};
// Verifies if there are any timer conflicts in the timers_in_use array
static constexpr bool verify_no_timer_conflicts() {
for (uint8_t i = 0; i < COUNT(timers_in_use); i++)
for (uint8_t j = i + 1; j < COUNT(timers_in_use); j++)
if (timers_in_use[i].t == timers_in_use[j].t)
return false;
return true;
}
// If this assertion fails at compile time, review the timers_in_use array.
// If default_envs is defined properly in platformio.ini, VSCode can evaluate the array
// when hovering over it, making it easy to identify the conflicting timers
static_assert(verify_no_timer_conflicts(), "One or more timer conflict detected. Examine \"timers_in_use\" to help identify conflict.");
#endif // ARDUINO_ARCH_MFL

View file

@ -0,0 +1,145 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../inc/MarlinConfig.h"
#include <GeneralTimer.h>
// ------------------------
// Defines
// ------------------------
// Timer configuration constants
#define STEPPER_TIMER_RATE 2000000
#define TEMP_TIMER_FREQUENCY 1000
// Timer instance definitions
#define MF_TIMER_STEP 3
#define MF_TIMER_TEMP 1
#define MF_TIMER_PULSE MF_TIMER_STEP
#define hal_timer_t uint32_t
#define HAL_TIMER_TYPE_MAX UINT16_MAX
extern uint32_t GetStepperTimerClkFreq();
// Timer prescaler calculations
#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
// Timer interrupt priorities
#define STEP_TIMER_IRQ_PRIORITY 2
#define TEMP_TIMER_IRQ_PRIORITY 14
#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)
extern void Step_Handler();
extern void Temp_Handler();
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() void Step_Handler()
#endif
#ifndef HAL_TEMP_TIMER_ISR
#define HAL_TEMP_TIMER_ISR() void Temp_Handler()
#endif
extern GeneralTimer& Step_Timer;
extern GeneralTimer& Temp_Timer;
extern bool is_step_timer_initialized;
extern bool is_temp_timer_initialized;
// Build-time mapping between timer base and index. Used in timers.cpp and fast_pwm.cpp
static inline constexpr struct {timer::TIMER_Base base; uint8_t timer_number;} base_to_index[] = {
{ timer::TIMER_Base::TIMER0_BASE, 0 },
{ timer::TIMER_Base::TIMER1_BASE, 1 },
{ timer::TIMER_Base::TIMER2_BASE, 2 },
{ timer::TIMER_Base::TIMER3_BASE, 3 },
{ timer::TIMER_Base::TIMER4_BASE, 4 },
{ timer::TIMER_Base::TIMER5_BASE, 5 },
{ timer::TIMER_Base::TIMER6_BASE, 6 },
{ timer::TIMER_Base::TIMER7_BASE, 7 }
};
// Converts a timer base to an integer timer index.
constexpr int timer_base_to_index(timer::TIMER_Base base) {
for (const auto& timer : base_to_index) {
if (timer.base == base) {
return static_cast<int>(timer.timer_number);
}
}
return -1;
}
// ------------------------
// Public functions
// ------------------------
void HAL_timer_start(const uint8_t timer, const uint32_t frequency);
void HAL_timer_enable_interrupt(const uint8_t timer);
void HAL_timer_disable_interrupt(const uint8_t timer);
bool HAL_timer_interrupt_enabled(const uint8_t timer);
// Configure timer priorities for peripherals such as Software Serial or Servos.
// Exposed here to allow all timer priority information to reside in timers.cpp
void SetTimerInterruptPriorities();
// FORCE_INLINE because these are used in performance-critical situations
FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_number) {
return (timer_number == MF_TIMER_STEP) ? is_step_timer_initialized :
(timer_number == MF_TIMER_TEMP) ? is_temp_timer_initialized :
false;
}
FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_number) {
if (!HAL_timer_initialized(timer_number)) return 0U;
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
return (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP)
? timer.getCounter(TimerFormat::TICK)
: 0U;
}
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_number, const hal_timer_t value) {
if (!HAL_timer_initialized(timer_number)) return;
const uint32_t new_value = static_cast<uint32_t>(value + 1U);
GeneralTimer& timer = (timer_number == MF_TIMER_STEP) ? Step_Timer : Temp_Timer;
if (timer_number == MF_TIMER_STEP || timer_number == MF_TIMER_TEMP) {
timer.setRolloverValue(new_value, TimerFormat::TICK);
if (value < static_cast<hal_timer_t>(timer.getCounter(TimerFormat::TICK)))
timer.refresh();
}
}
#define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) NOOP

View file

@ -0,0 +1,26 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
// MFL LCD-specific defines
uint8_t u8g_com_HAL_MFL_sw_spi_fn(u8g_t* u8g, uint8_t msg, uint8_t arg_val, void* arg_ptr); // u8g_com_mfl_swspi.cpp
#define U8G_COM_HAL_SW_SPI_FN u8g_com_HAL_MFL_sw_spi_fn

View file

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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

View file

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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

View file

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2023 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

View file

@ -33,8 +33,8 @@ void sei() { } // Enable
// Time functions
void _delay_ms(const int ms) { delay(ms); }
uint32_t millis() {
return (uint32_t)Clock::millis();
unsigned long millis() {
return (unsigned long)Clock::millis();
}
// This is required for some Arduino libraries we are using

View file

@ -76,9 +76,9 @@ extern "C" {
extern "C" void delay(const int ms);
void _delay_ms(const int ms);
void delayMicroseconds(unsigned long);
uint32_t millis();
unsigned long millis();
//IO functions
// IO functions
void pinMode(const pin_t, const uint8_t);
void digitalWrite(pin_t, uint8_t);
bool digitalRead(pin_t);

View file

@ -28,7 +28,7 @@
#include "../include/i2c_util.h"
#include "../../../core/millis_t.h"
extern int millis();
uint32_t millis();
#ifdef __cplusplus
extern "C" {

View file

@ -107,7 +107,7 @@ uint8_t get_pin_mode(const pin_t Ard_num) {
uint dir = gpio_get_dir( Ard_num);
if(dir) return MODE_PIN_OUTPUT;
if (dir) return MODE_PIN_OUTPUT;
else return MODE_PIN_INPUT;
}

View file

@ -145,7 +145,7 @@ bool SDIO_ReadBlock(uint32_t blockAddress, uint8_t *data) {
return false;
}
uint32_t millis();
unsigned long millis();
bool SDIO_WriteBlock(uint32_t blockAddress, const uint8_t *data) {
if (SDIO_GetCardState() != SDIO_CARD_TRANSFER) return false;

View file

@ -37,10 +37,20 @@
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT);
#else
#error "SERIAL_PORT must be from 0 to 3."
#endif
#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_2);
#endif
#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_3);
#endif
#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(MMU_SERIAL_PORT);
#endif
#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(LCD_SERIAL_PORT);
#endif
USBSerialType USBSerial(false, SerialUSB);

View file

@ -37,10 +37,21 @@
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT);
#endif
#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_2);
#endif
#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_3);
#endif
#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(MMU_SERIAL_PORT);
#endif
#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(LCD_SERIAL_PORT);
#endif
USBSerialType USBSerial(false, SerialUSB);
// ------------------------

View file

@ -39,18 +39,20 @@
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 8)
#if WITHIN(SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT);
#endif
#ifdef SERIAL_PORT_2
#if WITHIN(SERIAL_PORT_2, 0, 8)
IMPLEMENT_SERIAL(SERIAL_PORT_2);
#endif
#if defined(SERIAL_PORT_2) && WITHIN(SERIAL_PORT_2, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_2);
#endif
#ifdef SERIAL_PORT_3
#if WITHIN(SERIAL_PORT_3, 0, 8)
IMPLEMENT_SERIAL(SERIAL_PORT_3);
#endif
#if defined(SERIAL_PORT_3) && WITHIN(SERIAL_PORT_3, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(SERIAL_PORT_3);
#endif
#if defined(MMU_SERIAL_PORT) && WITHIN(MMU_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(MMU_SERIAL_PORT);
#endif
#if defined(LCD_SERIAL_PORT) && WITHIN(LCD_SERIAL_PORT, SERIAL_INDEX_MIN, SERIAL_INDEX_MAX)
IMPLEMENT_SERIAL(LCD_SERIAL_PORT);
#endif
USBSerialType USBSerial(false, SerialUSB);

View file

@ -37,6 +37,8 @@
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME)
#elif defined(ARDUINO_ARCH_HC32)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/HC32/NAME)
#elif defined(ARDUINO_ARCH_MFL)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/GD32_MFL/NAME)
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
#define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME)
#elif defined(ARDUINO_ARCH_STM32)

View file

@ -76,6 +76,8 @@
#include "../LPC1768/Servo.h"
#elif defined(ARDUINO_ARCH_HC32)
#include "../HC32/Servo.h"
#elif defined(ARDUINO_ARCH_MFL)
#include "../GD32_MFL/Servo.h"
#elif defined(__STM32F1__) || defined(TARGET_STM32F1)
#include "../STM32F1/Servo.h"
#elif defined(ARDUINO_ARCH_STM32)

View file

@ -271,6 +271,10 @@
PGMSTR(M112_KILL_STR, "M112 Shutdown");
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
MString<64> machine_name;
#endif
MarlinState marlin_state = MarlinState::MF_INITIALIZING;
// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop
@ -674,14 +678,14 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
TERN_(HOTEND_IDLE_TIMEOUT, hotend_idle.check());
#if ANY(PSU_CONTROL, AUTO_POWER_CONTROL) && PIN_EXISTS(PS_ON_EDM)
if ( ELAPSED(ms, powerManager.last_state_change_ms + PS_EDM_RESPONSE)
if ( ELAPSED(ms, powerManager.last_state_change_ms, PS_EDM_RESPONSE)
&& (READ(PS_ON_PIN) != READ(PS_ON_EDM_PIN) || TERN0(PSU_OFF_REDUNDANT, extDigitalRead(PS_ON1_PIN) != extDigitalRead(PS_ON1_EDM_PIN)))
) kill(GET_TEXT_F(MSG_POWER_EDM_FAULT));
#endif
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
if (thermalManager.degHotend(active_extruder) > (EXTRUDER_RUNOUT_MINTEMP)
&& ELAPSED(ms, gcode.previous_move_ms + SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS))
&& ELAPSED(ms, gcode.previous_move_ms, SEC_TO_MS(EXTRUDER_RUNOUT_SECONDS))
&& !planner.has_blocks_queued()
) {
const int8_t e_stepper = TERN(HAS_SWITCHING_EXTRUDER, active_extruder >> 1, active_extruder);
@ -732,7 +736,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
WRITE(FET_SAFETY_PIN, FET_SAFETY_INVERTED);
}
#endif
}
} // manage_inactivity()
#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER)
#include "feature/babystep.h"
@ -886,7 +890,7 @@ void idle(const bool no_stepper_sleep/*=false*/) {
TERN_(MARLIN_DEV_MODE, idle_depth--);
return;
}
} // idle()
/**
* Kill all activity and lock the machine.
@ -979,7 +983,7 @@ void stop() {
safe_delay(350); // allow enough time for messages to get out before stopping
marlin_state = MarlinState::MF_STOPPED;
}
}
} // stop()
inline void tmc_standby_setup() {
#if PIN_EXISTS(X_STDBY)
@ -1048,7 +1052,7 @@ inline void tmc_standby_setup() {
#if PIN_EXISTS(E7_STDBY)
SET_INPUT_PULLDOWN(E7_STDBY_PIN);
#endif
}
} // tmc_standby_setup()
/**
* Marlin Firmware entry-point. Abandon Hope All Ye Who Enter Here.
@ -1363,6 +1367,10 @@ void setup() {
SETUP_RUN(settings.first_load()); // Load data from EEPROM if available (or use defaults)
// This also updates variables in the planner, elsewhere
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
SETUP_RUN(ui.reset_status(false)); // machine_name Initialized by settings.load()
#endif
#if ENABLED(PROBE_TARE)
SETUP_RUN(probe.tare_init());
#endif
@ -1694,7 +1702,7 @@ void setup() {
SETUP_LOG("setup() completed.");
TERN_(MARLIN_TEST_BUILD, runStartupTests());
}
} // setup()
/**
* The main Marlin program loop

View file

@ -41,6 +41,10 @@ inline void idle_no_sleep() { idle(true); }
void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false);
void minkill(const bool steppers_off=false);
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
extern MString<64> machine_name;
#endif
// Global State of the firmware
enum class MarlinState : uint8_t {
MF_INITIALIZING = 0,

View file

@ -383,7 +383,7 @@
#define BOARD_CHITU3D_V6 5036 // Chitu3D TronXY X5SA V6 Board (STM32F103ZE)
#define BOARD_CHITU3D_V9 5037 // Chitu3D TronXY X5SA V9 Board (STM32F103ZE)
#define BOARD_CREALITY_V4 5038 // Creality v4.x (STM32F103RC / STM32F103RE)
#define BOARD_CREALITY_V422 5039 // Creality v4.2.2 (STM32F103RC / STM32F103RE)
#define BOARD_CREALITY_V422 5039 // Creality v4.2.2 (STM32F103RC / STM32F103RE) ... GD32 Variant Below!
#define BOARD_CREALITY_V423 5040 // Creality v4.2.3 (STM32F103RC / STM32F103RE)
#define BOARD_CREALITY_V425 5041 // Creality v4.2.5 (STM32F103RC / STM32F103RE)
#define BOARD_CREALITY_V427 5042 // Creality v4.2.7 (STM32F103RC / STM32F103RE)
@ -553,12 +553,18 @@
#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)
//
// GD32 ARM Cortex-M4
//
#define BOARD_CREALITY_V422_GD32_MFL 7300 // Creality V4.2.2 MFL (GD32F303RE) ... STM32 Variant Above!
//
// Raspberry Pi
//
#define BOARD_RP2040 6200 // Generic RP2040 Test board
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
#define BOARD_RP2040 6200 // Generic RP2040 Test board
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
//
// Custom board

View file

@ -88,6 +88,7 @@
#undef MACHINE_NAME
#define MACHINE_NAME DEFAULT_MACHINE_NAME
#endif
#define MACHINE_NAME_SUBST TERN(CONFIGURABLE_MACHINE_NAME, "$", MACHINE_NAME)
#define MARLIN_WEBSITE_URL "marlinfw.org"
@ -311,8 +312,9 @@
#define STR_FILAMENT_RUNOUT_SENSOR "Filament runout sensor"
#define STR_DRIVER_STEPPING_MODE "Driver stepping mode"
#define STR_STEPPER_DRIVER_CURRENT "Stepper driver current"
#define STR_HOMING_CURRENT "Homing Current (mA)"
#define STR_HYBRID_THRESHOLD "Hybrid Threshold"
#define STR_STALLGUARD_THRESHOLD "StallGuard threshold"
#define STR_STALLGUARD_THRESHOLD "StallGuard Threshold"
#define STR_HOME_OFFSET "Home offset"
#define STR_SOFT_ENDSTOPS "Soft endstops"
#define STR_MATERIAL_HEATUP "Material heatup parameters"

View file

@ -206,19 +206,23 @@
#define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION ? 'A' : 'B'
#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION ? 'A' : '0'
#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION ? 'A' : '1'
#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION ? 'A' : '<nul>'
#define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1'
#define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1'
#define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B.
#define IF_DISABLED(O,A) TERN(O,,A)
// "Ternary" that emits or omits the given content
#define EMIT(V...) V
#define OMIT(...)
#define TERN_(O,A) _TERN(_ENA_1(O),OMIT,EMIT)(A) // OPTION ? 'A' : '<nul>'
// Macros to conditionally emit array items and function arguments
#define _OPTITEM(A...) A,
#define OPTITEM(O,A...) TERN_(O,DEFER4(_OPTITEM)(A))
#define OPTITEM(O,A...) TERN_(O,DEFER(_OPTITEM)(A))
#define _OPTARG(A...) , A
#define OPTARG(O,A...) TERN_(O,DEFER4(_OPTARG)(A))
#define OPTARG(O,A...) TERN_(O,DEFER(_OPTARG)(A))
#define _OPTCODE(A) A;
#define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A))
#define OPTCODE(O,A) TERN_(O,DEFER(_OPTCODE)(A))
// Macros to avoid operations that aren't always optimized away (e.g., 'f + 0.0' and 'f * 1.0').
// Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc.

View file

@ -30,5 +30,7 @@ typedef uint32_t millis_t;
#define MS_TO_SEC(N) millis_t((N)/1000UL)
#define MS_TO_SEC_PRECISE(N) (float(N)/1000.0f)
#define PENDING(NOW,SOON) ((int32_t)(NOW-(SOON))<0)
#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
constexpr bool _PENDING(const millis_t now, const millis_t when) { return int32_t(when - now) > 0; }
constexpr bool _PENDING(const millis_t now, const millis_t start, const millis_t interval) { return (now - start) < interval; }
#define PENDING(V...) _PENDING(V)
#define ELAPSED(V...) !_PENDING(V)

View file

@ -298,6 +298,9 @@ public:
MString& clear() { return set(); }
MString& eol() { return append('\n'); }
MString& trunc(const int &i) { if (i <= SIZE) str[i] = '\0'; debug(F("trunc")); return *this; }
MString& ltrim() { char *s = str; while (*s == ' ') ++s; if (s != str) strcpy(str, s); return *this; }
MString& rtrim() { int s = length(); while (s && str[s - 1] == ' ') --s; str[s] = '\0'; return *this; }
MString& trim() { return rtrim().ltrim(); }
// Truncate on a Unicode boundary
MString& utrunc(const int &n=SIZE) {

View file

@ -566,11 +566,11 @@ struct XYval {
FI XYval<T>& operator= (const XYZEval<T> &rs) { set(XY_LIST(rs.x, rs.y)); return *this; }
// Override other operators to get intuitive behaviors
#define XY_OP(OP) { x TERN_(HAS_X_AXIS, OP rs.x), y TERN_(HAS_Y_AXIS, OP rs.y) }
FI constexpr XYval<T> operator+ (const XYval<T> &rs) const { return { x + rs.x, y + rs.y }; }
FI constexpr XYval<T> operator- (const XYval<T> &rs) const { return { x - rs.x, y - rs.y }; }
FI constexpr XYval<T> operator* (const XYval<T> &rs) const { return { x * rs.x, y * rs.y }; }
FI constexpr XYval<T> operator/ (const XYval<T> &rs) const { return { x / rs.x, y / rs.y }; }
#define XY_OP(OP) { T(x TERN_(HAS_X_AXIS, OP rs.x)), T(y TERN_(HAS_Y_AXIS, OP rs.y)) }
FI constexpr XYval<T> operator+ (const XYval<T> &rs) const { return { T(x + rs.x), T(y + rs.y) }; }
FI constexpr XYval<T> operator- (const XYval<T> &rs) const { return { T(x - rs.x), T(y - rs.y) }; }
FI constexpr XYval<T> operator* (const XYval<T> &rs) const { return { T(x * rs.x), T(y * rs.y) }; }
FI constexpr XYval<T> operator/ (const XYval<T> &rs) const { return { T(x / rs.x), T(y / rs.y) }; }
FI constexpr XYval<T> operator+ (const XYZval<T> &rs) const { return { XY_OP(+) }; }
FI constexpr XYval<T> operator- (const XYZval<T> &rs) const { return { XY_OP(-) }; }
FI constexpr XYval<T> operator* (const XYZval<T> &rs) const { return { XY_OP(*) }; }
@ -721,21 +721,21 @@ struct XYZval {
FI XYZval<T>& operator= (const XYZEval<T> &rs) { set(NUM_AXIS_ELEM_LC(rs)); return *this; }
// Override other operators to get intuitive behaviors
FI constexpr XYZval<T> operator+ (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator- (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator* (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator/ (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator+ (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w ); }
FI constexpr XYZval<T> operator- (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w ); }
FI constexpr XYZval<T> operator* (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w ); }
FI constexpr XYZval<T> operator/ (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w ); }
FI constexpr XYZval<T> operator+ (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w ); }
FI constexpr XYZval<T> operator- (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w ); }
FI constexpr XYZval<T> operator* (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w ); }
FI constexpr XYZval<T> operator/ (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w ); }
FI constexpr XYZval<T> operator* (const float &p) const { return NUM_AXIS_ARRAY((T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); }
FI constexpr XYZval<T> operator+ (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator- (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator* (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator/ (const XYval<T> &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), z, i, j, k, u, v, w ); }
FI constexpr XYZval<T> operator+ (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w) ); }
FI constexpr XYZval<T> operator- (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w) ); }
FI constexpr XYZval<T> operator* (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w) ); }
FI constexpr XYZval<T> operator/ (const XYZval<T> &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w) ); }
FI constexpr XYZval<T> operator+ (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w) ); }
FI constexpr XYZval<T> operator- (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w) ); }
FI constexpr XYZval<T> operator* (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w) ); }
FI constexpr XYZval<T> operator/ (const XYZEval<T> &rs) const { return NUM_AXIS_ARRAY(T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w) ); }
FI constexpr XYZval<T> operator* (const float &p) const { return NUM_AXIS_ARRAY(T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); }
FI constexpr XYZval<T> operator* (const int &p) const { return NUM_AXIS_ARRAY(x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); }
FI constexpr XYZval<T> operator/ (const float &p) const { return NUM_AXIS_ARRAY((T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); }
FI constexpr XYZval<T> operator/ (const float &p) const { return NUM_AXIS_ARRAY(T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); }
FI constexpr XYZval<T> operator/ (const int &p) const { return NUM_AXIS_ARRAY(x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); }
FI constexpr XYZval<T> operator>>(const int &p) const { return NUM_AXIS_ARRAY(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); }
FI constexpr XYZval<T> operator<<(const int &p) const { return NUM_AXIS_ARRAY(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); }
@ -870,21 +870,21 @@ struct XYZEval {
FI XYZEval<T>& operator= (const XYZval<T> &rs) { set(NUM_AXIS_ELEM_LC(rs)); return *this; }
// Override other operators to get intuitive behaviors
FI constexpr XYZEval<T> operator+ (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x + rs.x, y + rs.y, z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator- (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x - rs.x, y - rs.y, z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator* (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x * rs.x, y * rs.y, z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator/ (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x / rs.x, y / rs.y, z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator+ (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w); }
FI constexpr XYZEval<T> operator- (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w); }
FI constexpr XYZEval<T> operator* (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w); }
FI constexpr XYZEval<T> operator/ (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w); }
FI constexpr XYZEval<T> operator+ (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e + rs.e, x + rs.x, y + rs.y, z + rs.z, i + rs.i, j + rs.j, k + rs.k, u + rs.u, v + rs.v, w + rs.w); }
FI constexpr XYZEval<T> operator- (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e - rs.e, x - rs.x, y - rs.y, z - rs.z, i - rs.i, j - rs.j, k - rs.k, u - rs.u, v - rs.v, w - rs.w); }
FI constexpr XYZEval<T> operator* (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e * rs.e, x * rs.x, y * rs.y, z * rs.z, i * rs.i, j * rs.j, k * rs.k, u * rs.u, v * rs.v, w * rs.w); }
FI constexpr XYZEval<T> operator/ (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e / rs.e, x / rs.x, y / rs.y, z / rs.z, i / rs.i, j / rs.j, k / rs.k, u / rs.u, v / rs.v, w / rs.w); }
FI constexpr XYZEval<T> operator* (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e * p), (T)(x * p), (T)(y * p), (T)(z * p), (T)(i * p), (T)(j * p), (T)(k * p), (T)(u * p), (T)(v * p), (T)(w * p)); }
FI constexpr XYZEval<T> operator+ (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x + rs.x), T(y + rs.y), z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator- (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x - rs.x), T(y - rs.y), z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator* (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x * rs.x), T(y * rs.y), z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator/ (const XYval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x / rs.x), T(y / rs.y), z, i, j, k, u, v, w); }
FI constexpr XYZEval<T> operator+ (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w)); }
FI constexpr XYZEval<T> operator- (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); }
FI constexpr XYZEval<T> operator* (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); }
FI constexpr XYZEval<T> operator/ (const XYZval<T> &rs) const { return LOGICAL_AXIS_ARRAY(e, T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); }
FI constexpr XYZEval<T> operator+ (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e + rs.e), T(x + rs.x), T(y + rs.y), T(z + rs.z), T(i + rs.i), T(j + rs.j), T(k + rs.k), T(u + rs.u), T(v + rs.v), T(w + rs.w)); }
FI constexpr XYZEval<T> operator- (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e - rs.e), T(x - rs.x), T(y - rs.y), T(z - rs.z), T(i - rs.i), T(j - rs.j), T(k - rs.k), T(u - rs.u), T(v - rs.v), T(w - rs.w)); }
FI constexpr XYZEval<T> operator* (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e * rs.e), T(x * rs.x), T(y * rs.y), T(z * rs.z), T(i * rs.i), T(j * rs.j), T(k * rs.k), T(u * rs.u), T(v * rs.v), T(w * rs.w)); }
FI constexpr XYZEval<T> operator/ (const XYZEval<T> &rs) const { return LOGICAL_AXIS_ARRAY(T(e / rs.e), T(x / rs.x), T(y / rs.y), T(z / rs.z), T(i / rs.i), T(j / rs.j), T(k / rs.k), T(u / rs.u), T(v / rs.v), T(w / rs.w)); }
FI constexpr XYZEval<T> operator* (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e * p), T(x * p), T(y * p), T(z * p), T(i * p), T(j * p), T(k * p), T(u * p), T(v * p), T(w * p)); }
FI constexpr XYZEval<T> operator* (const int &p) const { return LOGICAL_AXIS_ARRAY(e * p, x * p, y * p, z * p, i * p, j * p, k * p, u * p, v * p, w * p); }
FI constexpr XYZEval<T> operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY((T)(e / p), (T)(x / p), (T)(y / p), (T)(z / p), (T)(i / p), (T)(j / p), (T)(k / p), (T)(u / p), (T)(v / p), (T)(w / p)); }
FI constexpr XYZEval<T> operator/ (const float &p) const { return LOGICAL_AXIS_ARRAY(T(e / p), T(x / p), T(y / p), T(z / p), T(i / p), T(j / p), T(k / p), T(u / p), T(v / p), T(w / p)); }
FI constexpr XYZEval<T> operator/ (const int &p) const { return LOGICAL_AXIS_ARRAY(e / p, x / p, y / p, z / p, i / p, j / p, k / p, u / p, v / p, w / p); }
FI constexpr XYZEval<T> operator>>(const int &p) const { return LOGICAL_AXIS_ARRAY(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k), _RS(u), _RS(v), _RS(w)); }
FI constexpr XYZEval<T> operator<<(const int &p) const { return LOGICAL_AXIS_ARRAY(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k), _LS(u), _LS(v), _LS(w)); }
@ -1231,3 +1231,14 @@ public:
#undef _LSE
#undef _RSE
#undef FI
// Axis names for G-code parsing, reports, etc.
constexpr xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME);
#if NUM_AXES <= XYZ && !HAS_EXTRUDERS
#define AXIS_CHAR(A) ((char)('X' + A))
#define IAXIS_CHAR AXIS_CHAR
#else
constexpr xyze_char_t iaxis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', 'I', 'J', 'K', 'U', 'V', 'W');
#define AXIS_CHAR(A) axis_codes[A]
#define IAXIS_CHAR(A) iaxis_codes[A]
#endif

View file

@ -82,17 +82,6 @@ public:
// in the range 0-100 while avoiding rounding artifacts
constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; }
// Axis names for G-code parsing, reports, etc.
const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME);
#if NUM_AXES <= XYZ && !HAS_EXTRUDERS
#define AXIS_CHAR(A) ((char)('X' + A))
#define IAXIS_CHAR AXIS_CHAR
#else
const xyze_char_t iaxis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', 'I', 'J', 'K', 'U', 'V', 'W');
#define AXIS_CHAR(A) axis_codes[A]
#define IAXIS_CHAR(A) iaxis_codes[A]
#endif
#if ENABLED(MARLIN_DEV_MODE)
enum MarlinError : uint8_t {
ERR_NONE,

View file

@ -87,7 +87,7 @@ void ControllerFan::update() {
* - If System is on idle and idle fan speed settings is activated.
*/
set_fan_speed(
settings.auto_mode && lastComponentOn && PENDING(ms, lastComponentOn + SEC_TO_MS(settings.duration))
settings.auto_mode && lastComponentOn && PENDING(ms, lastComponentOn, SEC_TO_MS(settings.duration))
? settings.active_speed : settings.idle_speed
);

View file

@ -87,13 +87,7 @@ void DigipotI2C::init() {
Wire.begin();
#endif
// Set up initial currents as defined in Configuration_adv.h
static const float digipot_motor_current[] PROGMEM =
#if ENABLED(DIGIPOT_USE_RAW_VALUES)
DIGIPOT_MOTOR_CURRENT
#else
DIGIPOT_I2C_MOTOR_CURRENTS
#endif
;
static const float digipot_motor_current[] PROGMEM = TERN(DIGIPOT_USE_RAW_VALUES, DIGIPOT_MOTOR_CURRENT, DIGIPOT_I2C_MOTOR_CURRENTS);
for (uint8_t i = 0; i < COUNT(digipot_motor_current); ++i)
set_current(i, pgm_read_float(&digipot_motor_current[i]));
}

View file

@ -78,9 +78,9 @@ void EasythreedUI::blinkLED() {
prev_blink_interval_ms = blink_interval_ms;
blink_start_ms = ms;
}
if (PENDING(ms, blink_start_ms + blink_interval_ms))
if (PENDING(ms, blink_start_ms, blink_interval_ms))
WRITE(EASYTHREED_LED_PIN, LOW);
else if (PENDING(ms, blink_start_ms + 2 * blink_interval_ms))
else if (PENDING(ms, blink_start_ms, 2 * blink_interval_ms))
WRITE(EASYTHREED_LED_PIN, HIGH);
else
blink_start_ms = ms;
@ -107,7 +107,7 @@ void EasythreedUI::loadButton() {
break;
case FS_PRESS:
if (ELAPSED(millis(), filament_time + BTN_DEBOUNCE_MS)) { // After a short debounce delay...
if (ELAPSED(millis(), filament_time, BTN_DEBOUNCE_MS)) { // After a short debounce delay...
if (!READ(BTN_RETRACT) || !READ(BTN_FEED)) { // ...if switch still toggled...
thermalManager.setTargetHotend(EXTRUDE_MINTEMP + 10, 0); // Start heating up
blink_interval_ms = LED_BLINK_7; // Set the LED to blink fast
@ -175,14 +175,14 @@ void EasythreedUI::printButton() {
break;
case KS_PRESS:
if (ELAPSED(ms, key_time + BTN_DEBOUNCE_MS)) // Wait for debounce interval to expire
if (ELAPSED(ms, key_time, BTN_DEBOUNCE_MS)) // Wait for debounce interval to expire
key_status = READ(BTN_PRINT) ? KS_IDLE : KS_PROCEED; // Proceed if still pressed
break;
case KS_PROCEED:
if (!READ(BTN_PRINT)) break; // Wait for the button to be released
key_status = KS_IDLE; // Ready for the next press
if (PENDING(ms, key_time + 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds
if (PENDING(ms, key_time, 1200 - BTN_DEBOUNCE_MS)) { // Register a press < 1.2 seconds
switch (print_key_flag) {
case PF_START: { // The "Print" button starts an SD card print
if (printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?')

View file

@ -480,32 +480,30 @@ void Max7219::register_setup() {
#if MAX7219_INIT_TEST
uint8_t test_mode = 0;
millis_t next_patt_ms;
bool patt_on;
#if MAX7219_INIT_TEST == 2
#define MAX7219_LEDS (MAX7219_X_LEDS * MAX7219_Y_LEDS)
constexpr millis_t pattern_delay = 4;
int8_t spiralx, spiraly, spiral_dir;
xy_int8_t spiral;
int8_t spiral_dir;
uvalue_t(MAX7219_LEDS) spiral_count;
void Max7219::test_pattern() {
constexpr int8_t way[][2] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } };
led_set(spiralx, spiraly, patt_on);
const int8_t x = spiralx + way[spiral_dir][0], y = spiraly + way[spiral_dir][1];
if (!WITHIN(x, 0, MAX7219_X_LEDS - 1) || !WITHIN(y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(x, y) == patt_on)
void Max7219::run_test_pattern() {
constexpr xy_int8_t way[] = { { 1, 0 }, { 0, 1 }, { -1, 0 }, { 0, -1 } };
led_set(spiral.x, spiral.y, patt_on);
const xy_int8_t xy = spiral + way[spiral_dir];
if (!WITHIN(xy.x, 0, MAX7219_X_LEDS - 1) || !WITHIN(xy.y, 0, MAX7219_Y_LEDS - 1) || BIT_7219(xy.x, xy.y) == patt_on)
spiral_dir = (spiral_dir + 1) & 0x3;
spiralx += way[spiral_dir][0];
spiraly += way[spiral_dir][1];
spiral += way[spiral_dir];
if (!spiral_count--) {
if (!patt_on)
test_mode = 0;
else {
spiral_count = MAX7219_LEDS;
spiralx = spiraly = spiral_dir = 0;
spiral.reset();
spiral_dir = 0;
patt_on = false;
}
}
@ -516,7 +514,11 @@ void Max7219::register_setup() {
constexpr millis_t pattern_delay = 20;
int8_t sweep_count, sweepx, sweep_dir;
void Max7219::test_pattern() {
void Max7219::run_test_pattern() {
static millis_t next_pattern_ms = 0;
const millis_t ms = millis();
if (PENDING(ms, next_pattern_ms)) return;
next_pattern_ms = ms + pattern_delay;
set_column(sweepx, patt_on ? 0xFFFFFFFF : 0x00000000);
sweepx += sweep_dir;
if (!WITHIN(sweepx, 0, MAX7219_X_LEDS - 1)) {
@ -527,26 +529,20 @@ void Max7219::register_setup() {
else
sweepx -= MAX7219_X_LEDS * sweep_dir;
FLIP(patt_on);
next_patt_ms += 100;
next_pattern_ms += 100;
if (++test_mode > 4) test_mode = 0;
}
}
#endif
void Max7219::run_test_pattern() {
const millis_t ms = millis();
if (PENDING(ms, next_patt_ms)) return;
next_patt_ms = ms + pattern_delay;
test_pattern();
}
void Max7219::start_test_pattern() {
clear();
test_mode = 1;
patt_on = true;
#if MAX7219_INIT_TEST == 2
spiralx = spiraly = spiral_dir = 0;
spiral.reset();
spiral_dir = 0;
spiral_count = MAX7219_LEDS;
#else
sweep_dir = 1;

View file

@ -110,7 +110,7 @@
if (mode == ACCUMULATE_TOTAL) return;
// update time_fraction every hundred milliseconds
if (instance_count == 0 && ELAPSED(now, last_calc_time + 100000)) {
if (instance_count == 0 && now - last_calc_time > 100000) {
time_fraction = total_time * 128 / (now - last_calc_time);
last_calc_time = now;
total_time = 0;

View file

@ -164,7 +164,7 @@ void MMU2::mmu_loop() {
MMU2_SEND("S1"); // Read Version
state = -2;
}
else if (ELAPSED(millis(), prev_request + 30000)) { // 30sec after reset disable MMU
else if (ELAPSED(millis(), prev_request, 30000)) { // 30sec after reset disable MMU
SERIAL_ECHOLNPGM("MMU not responding - DISABLED");
state = 0;
}
@ -276,7 +276,7 @@ void MMU2::mmu_loop() {
last_cmd = cmd;
cmd = MMU_CMD_NONE;
}
else if (ELAPSED(millis(), prev_P0_request + 300)) {
else if (ELAPSED(millis(), prev_P0_request, 300)) {
MMU2_SEND("P0"); // Read FINDA
state = 2; // wait for response
}
@ -296,7 +296,7 @@ void MMU2::mmu_loop() {
if (cmd == MMU_CMD_NONE) ready = true;
state = 1;
}
else if (ELAPSED(millis(), prev_request + MMU_P0_TIMEOUT)) // Resend request after timeout (3s)
else if (ELAPSED(millis(), prev_request, MMU_P0_TIMEOUT)) // Resend request after timeout (3s)
state = 1;
TERN_(HAS_PRUSA_MMU2S, check_filament());
@ -335,7 +335,7 @@ void MMU2::mmu_loop() {
last_cmd = MMU_CMD_NONE;
}
}
else if (ELAPSED(millis(), prev_request + MMU_CMD_TIMEOUT)) {
else if (ELAPSED(millis(), prev_request, MMU_CMD_TIMEOUT)) {
// resend request after timeout
if (last_cmd) {
DEBUG_ECHOLNPGM("MMU retry");

View file

@ -261,7 +261,7 @@ void Power::power_off() {
nextPowerCheck = now + 2500UL;
if (is_power_needed())
power_on();
else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn + SEC_TO_MS(POWER_TIMEOUT))))
else if (!lastPowerOn || (POWER_TIMEOUT > 0 && ELAPSED(now, lastPowerOn, SEC_TO_MS(POWER_TIMEOUT))))
power_off();
}
}

View file

@ -43,6 +43,10 @@
#endif
#endif
#if ENABLED(EDITABLE_HOMING_CURRENT)
homing_current_t homing_current_mA;
#endif
/**
* Check for over temperature or short to ground error flags.
* Report and log warning of overtemperature condition.
@ -344,127 +348,70 @@
if (need_update_error_counters || need_debug_reporting) {
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2)
{
bool result = false;
#if AXIS_IS_TMC(X)
if (monitor_tmc_driver(stepperX, need_update_error_counters, need_debug_reporting)) result = true;
#endif
#if AXIS_IS_TMC(X2)
if (monitor_tmc_driver(stepperX2, need_update_error_counters, need_debug_reporting)) result = true;
#endif
if (result) {
#if AXIS_IS_TMC(X)
step_current_down(stepperX);
#endif
#if AXIS_IS_TMC(X2)
step_current_down(stepperX2);
#endif
#if X_IS_TRINAMIC || X2_IS_TRINAMIC
if ( TERN0(X_IS_TRINAMIC, monitor_tmc_driver(stepperX, need_update_error_counters, need_debug_reporting))
|| TERN0(X2_IS_TRINAMIC, monitor_tmc_driver(stepperX2, need_update_error_counters, need_debug_reporting))
) {
TERN_(X_IS_TRINAMIC, step_current_down(stepperX));
TERN_(X2_IS_TRINAMIC, step_current_down(stepperX2));
}
}
#endif
#if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2)
{
bool result = false;
#if AXIS_IS_TMC(Y)
if (monitor_tmc_driver(stepperY, need_update_error_counters, need_debug_reporting)) result = true;
#endif
#if AXIS_IS_TMC(Y2)
if (monitor_tmc_driver(stepperY2, need_update_error_counters, need_debug_reporting)) result = true;
#endif
if (result) {
#if AXIS_IS_TMC(Y)
step_current_down(stepperY);
#endif
#if AXIS_IS_TMC(Y2)
step_current_down(stepperY2);
#endif
#if Y_IS_TRINAMIC || Y2_IS_TRINAMIC
if ( TERN0(Y_IS_TRINAMIC, monitor_tmc_driver(stepperY, need_update_error_counters, need_debug_reporting))
|| TERN0(Y2_IS_TRINAMIC, monitor_tmc_driver(stepperY2, need_update_error_counters, need_debug_reporting))
) {
TERN_(Y_IS_TRINAMIC, step_current_down(stepperY));
TERN_(Y2_IS_TRINAMIC, step_current_down(stepperY2));
}
}
#endif
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
{
bool result = false;
#if AXIS_IS_TMC(Z)
if (monitor_tmc_driver(stepperZ, need_update_error_counters, need_debug_reporting)) result = true;
#endif
#if AXIS_IS_TMC(Z2)
if (monitor_tmc_driver(stepperZ2, need_update_error_counters, need_debug_reporting)) result = true;
#endif
#if AXIS_IS_TMC(Z3)
if (monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) result = true;
#endif
#if AXIS_IS_TMC(Z4)
if (monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting)) result = true;
#endif
if (result) {
#if AXIS_IS_TMC(Z)
step_current_down(stepperZ);
#endif
#if AXIS_IS_TMC(Z2)
step_current_down(stepperZ2);
#endif
#if AXIS_IS_TMC(Z3)
step_current_down(stepperZ3);
#endif
#if AXIS_IS_TMC(Z4)
step_current_down(stepperZ4);
#endif
#if ANY(Z_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
if ( TERN0(Z_IS_TRINAMIC, monitor_tmc_driver(stepperZ, need_update_error_counters, need_debug_reporting))
|| TERN0(Z2_IS_TRINAMIC, monitor_tmc_driver(stepperZ2, need_update_error_counters, need_debug_reporting))
|| TERN0(Z3_IS_TRINAMIC, monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting))
|| TERN0(Z4_IS_TRINAMIC, monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting))
) {
TERN_(Z_IS_TRINAMIC, step_current_down(stepperZ));
TERN_(Z2_IS_TRINAMIC, step_current_down(stepperZ2));
TERN_(Z3_IS_TRINAMIC, step_current_down(stepperZ3));
TERN_(Z4_IS_TRINAMIC, step_current_down(stepperZ4));
}
}
#endif
#if AXIS_IS_TMC(I)
#if I_IS_TRINAMIC
if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting))
step_current_down(stepperI);
#endif
#if AXIS_IS_TMC(J)
#if J_IS_TRINAMIC
if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting))
step_current_down(stepperJ);
#endif
#if AXIS_IS_TMC(K)
#if K_IS_TRINAMIC
if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting))
step_current_down(stepperK);
#endif
#if AXIS_IS_TMC(U)
#if U_IS_TRINAMIC
if (monitor_tmc_driver(stepperU, need_update_error_counters, need_debug_reporting))
step_current_down(stepperU);
#endif
#if AXIS_IS_TMC(V)
#if V_IS_TRINAMIC
if (monitor_tmc_driver(stepperV, need_update_error_counters, need_debug_reporting))
step_current_down(stepperV);
#endif
#if AXIS_IS_TMC(W)
#if W_IS_TRINAMIC
if (monitor_tmc_driver(stepperW, need_update_error_counters, need_debug_reporting))
step_current_down(stepperW);
#endif
#if AXIS_IS_TMC(E0)
(void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E1)
(void)monitor_tmc_driver(stepperE1, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E2)
(void)monitor_tmc_driver(stepperE2, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E3)
(void)monitor_tmc_driver(stepperE3, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E4)
(void)monitor_tmc_driver(stepperE4, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E5)
(void)monitor_tmc_driver(stepperE5, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E6)
(void)monitor_tmc_driver(stepperE6, need_update_error_counters, need_debug_reporting);
#endif
#if AXIS_IS_TMC(E7)
(void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting);
#endif
TERN_(E0_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting));
TERN_(E1_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE1, need_update_error_counters, need_debug_reporting));
TERN_(E2_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE2, need_update_error_counters, need_debug_reporting));
TERN_(E3_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE3, need_update_error_counters, need_debug_reporting));
TERN_(E4_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE4, need_update_error_counters, need_debug_reporting));
TERN_(E5_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE5, need_update_error_counters, need_debug_reporting));
TERN_(E6_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE6, need_update_error_counters, need_debug_reporting));
TERN_(E7_IS_TRINAMIC, (void)monitor_tmc_driver(stepperE7, need_update_error_counters, need_debug_reporting));
if (TERN0(TMC_DEBUG, need_debug_reporting)) SERIAL_EOL();
}
@ -781,82 +728,38 @@
static void tmc_debug_loop(const TMC_debug_enum n OPTARGS_LOGICAL(const bool)) {
if (TERN0(HAS_X_AXIS, x)) {
#if AXIS_IS_TMC(X)
tmc_status(stepperX, n);
#endif
#if AXIS_IS_TMC(X2)
tmc_status(stepperX2, n);
#endif
TERN_(X_IS_TRINAMIC, tmc_status(stepperX, n));
TERN_(X2_IS_TRINAMIC, tmc_status(stepperX2, n));
}
if (TERN0(HAS_Y_AXIS, y)) {
#if AXIS_IS_TMC(Y)
tmc_status(stepperY, n);
#endif
#if AXIS_IS_TMC(Y2)
tmc_status(stepperY2, n);
#endif
TERN_(Y_IS_TRINAMIC, tmc_status(stepperY, n));
TERN_(Y2_IS_TRINAMIC, tmc_status(stepperY2, n));
}
if (TERN0(HAS_Z_AXIS, z)) {
#if AXIS_IS_TMC(Z)
tmc_status(stepperZ, n);
#endif
#if AXIS_IS_TMC(Z2)
tmc_status(stepperZ2, n);
#endif
#if AXIS_IS_TMC(Z3)
tmc_status(stepperZ3, n);
#endif
#if AXIS_IS_TMC(Z4)
tmc_status(stepperZ4, n);
#endif
TERN_(Z_IS_TRINAMIC, tmc_status(stepperZ, n));
TERN_(Z2_IS_TRINAMIC, tmc_status(stepperZ2, n));
TERN_(Z3_IS_TRINAMIC, tmc_status(stepperZ3, n));
TERN_(Z4_IS_TRINAMIC, tmc_status(stepperZ4, n));
}
#if AXIS_IS_TMC(I)
if (i) tmc_status(stepperI, n);
#endif
#if AXIS_IS_TMC(J)
if (j) tmc_status(stepperJ, n);
#endif
#if AXIS_IS_TMC(K)
if (k) tmc_status(stepperK, n);
#endif
#if AXIS_IS_TMC(U)
if (u) tmc_status(stepperU, n);
#endif
#if AXIS_IS_TMC(V)
if (v) tmc_status(stepperV, n);
#endif
#if AXIS_IS_TMC(W)
if (w) tmc_status(stepperW, n);
#endif
TERN_(I_IS_TRINAMIC, if (i) tmc_status(stepperI, n));
TERN_(J_IS_TRINAMIC, if (j) tmc_status(stepperJ, n));
TERN_(K_IS_TRINAMIC, if (k) tmc_status(stepperK, n));
TERN_(U_IS_TRINAMIC, if (u) tmc_status(stepperU, n));
TERN_(V_IS_TRINAMIC, if (v) tmc_status(stepperV, n));
TERN_(W_IS_TRINAMIC, if (w) tmc_status(stepperW, n));
if (TERN0(HAS_EXTRUDERS, e)) {
#if AXIS_IS_TMC(E0)
tmc_status(stepperE0, n);
#endif
#if AXIS_IS_TMC(E1)
tmc_status(stepperE1, n);
#endif
#if AXIS_IS_TMC(E2)
tmc_status(stepperE2, n);
#endif
#if AXIS_IS_TMC(E3)
tmc_status(stepperE3, n);
#endif
#if AXIS_IS_TMC(E4)
tmc_status(stepperE4, n);
#endif
#if AXIS_IS_TMC(E5)
tmc_status(stepperE5, n);
#endif
#if AXIS_IS_TMC(E6)
tmc_status(stepperE6, n);
#endif
#if AXIS_IS_TMC(E7)
tmc_status(stepperE7, n);
#endif
TERN_(E0_IS_TRINAMIC, tmc_status(stepperE0, n));
TERN_(E1_IS_TRINAMIC, tmc_status(stepperE1, n));
TERN_(E2_IS_TRINAMIC, tmc_status(stepperE2, n));
TERN_(E3_IS_TRINAMIC, tmc_status(stepperE3, n));
TERN_(E4_IS_TRINAMIC, tmc_status(stepperE4, n));
TERN_(E5_IS_TRINAMIC, tmc_status(stepperE5, n));
TERN_(E6_IS_TRINAMIC, tmc_status(stepperE6, n));
TERN_(E7_IS_TRINAMIC, tmc_status(stepperE7, n));
}
SERIAL_EOL();
@ -864,82 +767,38 @@
static void drv_status_loop(const TMC_drv_status_enum n OPTARGS_LOGICAL(const bool)) {
if (TERN0(HAS_X_AXIS, x)) {
#if AXIS_IS_TMC(X)
tmc_parse_drv_status(stepperX, n);
#endif
#if AXIS_IS_TMC(X2)
tmc_parse_drv_status(stepperX2, n);
#endif
TERN_(X_IS_TRINAMIC, tmc_parse_drv_status(stepperX, n));
TERN_(X2_IS_TRINAMIC, tmc_parse_drv_status(stepperX2, n));
}
if (TERN0(HAS_Y_AXIS, y)) {
#if AXIS_IS_TMC(Y)
tmc_parse_drv_status(stepperY, n);
#endif
#if AXIS_IS_TMC(Y2)
tmc_parse_drv_status(stepperY2, n);
#endif
TERN_(Y_IS_TRINAMIC, tmc_parse_drv_status(stepperY, n));
TERN_(Y2_IS_TRINAMIC, tmc_parse_drv_status(stepperY2, n));
}
if (TERN0(HAS_Z_AXIS, z)) {
#if AXIS_IS_TMC(Z)
tmc_parse_drv_status(stepperZ, n);
#endif
#if AXIS_IS_TMC(Z2)
tmc_parse_drv_status(stepperZ2, n);
#endif
#if AXIS_IS_TMC(Z3)
tmc_parse_drv_status(stepperZ3, n);
#endif
#if AXIS_IS_TMC(Z4)
tmc_parse_drv_status(stepperZ4, n);
#endif
TERN_(Z_IS_TRINAMIC, tmc_parse_drv_status(stepperZ, n));
TERN_(Z2_IS_TRINAMIC, tmc_parse_drv_status(stepperZ2, n));
TERN_(Z3_IS_TRINAMIC, tmc_parse_drv_status(stepperZ3, n));
TERN_(Z4_IS_TRINAMIC, tmc_parse_drv_status(stepperZ4, n));
}
#if AXIS_IS_TMC(I)
if (i) tmc_parse_drv_status(stepperI, n);
#endif
#if AXIS_IS_TMC(J)
if (j) tmc_parse_drv_status(stepperJ, n);
#endif
#if AXIS_IS_TMC(K)
if (k) tmc_parse_drv_status(stepperK, n);
#endif
#if AXIS_IS_TMC(U)
if (u) tmc_parse_drv_status(stepperU, n);
#endif
#if AXIS_IS_TMC(V)
if (v) tmc_parse_drv_status(stepperV, n);
#endif
#if AXIS_IS_TMC(W)
if (w) tmc_parse_drv_status(stepperW, n);
#endif
TERN_(I_IS_TRINAMIC, if (i) tmc_parse_drv_status(stepperI, n));
TERN_(J_IS_TRINAMIC, if (j) tmc_parse_drv_status(stepperJ, n));
TERN_(K_IS_TRINAMIC, if (k) tmc_parse_drv_status(stepperK, n));
TERN_(U_IS_TRINAMIC, if (u) tmc_parse_drv_status(stepperU, n));
TERN_(V_IS_TRINAMIC, if (v) tmc_parse_drv_status(stepperV, n));
TERN_(W_IS_TRINAMIC, if (w) tmc_parse_drv_status(stepperW, n));
if (TERN0(HAS_EXTRUDERS, e)) {
#if AXIS_IS_TMC(E0)
tmc_parse_drv_status(stepperE0, n);
#endif
#if AXIS_IS_TMC(E1)
tmc_parse_drv_status(stepperE1, n);
#endif
#if AXIS_IS_TMC(E2)
tmc_parse_drv_status(stepperE2, n);
#endif
#if AXIS_IS_TMC(E3)
tmc_parse_drv_status(stepperE3, n);
#endif
#if AXIS_IS_TMC(E4)
tmc_parse_drv_status(stepperE4, n);
#endif
#if AXIS_IS_TMC(E5)
tmc_parse_drv_status(stepperE5, n);
#endif
#if AXIS_IS_TMC(E6)
tmc_parse_drv_status(stepperE6, n);
#endif
#if AXIS_IS_TMC(E7)
tmc_parse_drv_status(stepperE7, n);
#endif
TERN_(E0_IS_TRINAMIC, tmc_parse_drv_status(stepperE0, n));
TERN_(E1_IS_TRINAMIC, tmc_parse_drv_status(stepperE1, n));
TERN_(E2_IS_TRINAMIC, tmc_parse_drv_status(stepperE2, n));
TERN_(E3_IS_TRINAMIC, tmc_parse_drv_status(stepperE3, n));
TERN_(E4_IS_TRINAMIC, tmc_parse_drv_status(stepperE4, n));
TERN_(E5_IS_TRINAMIC, tmc_parse_drv_status(stepperE5, n));
TERN_(E6_IS_TRINAMIC, tmc_parse_drv_status(stepperE6, n));
TERN_(E7_IS_TRINAMIC, tmc_parse_drv_status(stepperE7, n));
}
SERIAL_EOL();
@ -1078,82 +937,38 @@
static void tmc_get_registers(TMC_get_registers_enum n OPTARGS_LOGICAL(const bool)) {
if (TERN0(HAS_X_AXIS, x)) {
#if AXIS_IS_TMC(X)
tmc_get_registers(stepperX, n);
#endif
#if AXIS_IS_TMC(X2)
tmc_get_registers(stepperX2, n);
#endif
TERN_(X_IS_TRINAMIC, tmc_get_registers(stepperX, n));
TERN_(X2_IS_TRINAMIC, tmc_get_registers(stepperX2, n));
}
if (TERN0(HAS_Y_AXIS, y)) {
#if AXIS_IS_TMC(Y)
tmc_get_registers(stepperY, n);
#endif
#if AXIS_IS_TMC(Y2)
tmc_get_registers(stepperY2, n);
#endif
TERN_(Y_IS_TRINAMIC, tmc_get_registers(stepperY, n));
TERN_(Y2_IS_TRINAMIC, tmc_get_registers(stepperY2, n));
}
if (TERN0(HAS_Z_AXIS, z)) {
#if AXIS_IS_TMC(Z)
tmc_get_registers(stepperZ, n);
#endif
#if AXIS_IS_TMC(Z2)
tmc_get_registers(stepperZ2, n);
#endif
#if AXIS_IS_TMC(Z3)
tmc_get_registers(stepperZ3, n);
#endif
#if AXIS_IS_TMC(Z4)
tmc_get_registers(stepperZ4, n);
#endif
TERN_(Z_IS_TRINAMIC, tmc_get_registers(stepperZ, n));
TERN_(Z2_IS_TRINAMIC, tmc_get_registers(stepperZ2, n));
TERN_(Z3_IS_TRINAMIC, tmc_get_registers(stepperZ3, n));
TERN_(Z4_IS_TRINAMIC, tmc_get_registers(stepperZ4, n));
}
#if AXIS_IS_TMC(I)
if (i) tmc_get_registers(stepperI, n);
#endif
#if AXIS_IS_TMC(J)
if (j) tmc_get_registers(stepperJ, n);
#endif
#if AXIS_IS_TMC(K)
if (k) tmc_get_registers(stepperK, n);
#endif
#if AXIS_IS_TMC(U)
if (u) tmc_get_registers(stepperU, n);
#endif
#if AXIS_IS_TMC(V)
if (v) tmc_get_registers(stepperV, n);
#endif
#if AXIS_IS_TMC(W)
if (w) tmc_get_registers(stepperW, n);
#endif
TERN_(I_IS_TRINAMIC, if (i) tmc_get_registers(stepperI, n));
TERN_(J_IS_TRINAMIC, if (j) tmc_get_registers(stepperJ, n));
TERN_(K_IS_TRINAMIC, if (k) tmc_get_registers(stepperK, n));
TERN_(U_IS_TRINAMIC, if (u) tmc_get_registers(stepperU, n));
TERN_(V_IS_TRINAMIC, if (v) tmc_get_registers(stepperV, n));
TERN_(W_IS_TRINAMIC, if (w) tmc_get_registers(stepperW, n));
if (TERN0(HAS_EXTRUDERS, e)) {
#if AXIS_IS_TMC(E0)
tmc_get_registers(stepperE0, n);
#endif
#if AXIS_IS_TMC(E1)
tmc_get_registers(stepperE1, n);
#endif
#if AXIS_IS_TMC(E2)
tmc_get_registers(stepperE2, n);
#endif
#if AXIS_IS_TMC(E3)
tmc_get_registers(stepperE3, n);
#endif
#if AXIS_IS_TMC(E4)
tmc_get_registers(stepperE4, n);
#endif
#if AXIS_IS_TMC(E5)
tmc_get_registers(stepperE5, n);
#endif
#if AXIS_IS_TMC(E6)
tmc_get_registers(stepperE6, n);
#endif
#if AXIS_IS_TMC(E7)
tmc_get_registers(stepperE7, n);
#endif
TERN_(E0_IS_TRINAMIC, tmc_get_registers(stepperE0, n));
TERN_(E1_IS_TRINAMIC, tmc_get_registers(stepperE1, n));
TERN_(E2_IS_TRINAMIC, tmc_get_registers(stepperE2, n));
TERN_(E3_IS_TRINAMIC, tmc_get_registers(stepperE3, n));
TERN_(E4_IS_TRINAMIC, tmc_get_registers(stepperE4, n));
TERN_(E5_IS_TRINAMIC, tmc_get_registers(stepperE5, n));
TERN_(E6_IS_TRINAMIC, tmc_get_registers(stepperE6, n));
TERN_(E7_IS_TRINAMIC, tmc_get_registers(stepperE7, n));
}
SERIAL_EOL();
@ -1243,82 +1058,38 @@ void test_tmc_connection(LOGICAL_AXIS_ARGS_LC(const bool)) {
uint8_t axis_connection = 0;
if (TERN0(HAS_X_AXIS, x)) {
#if AXIS_IS_TMC(X)
axis_connection += test_connection(stepperX);
#endif
#if AXIS_IS_TMC(X2)
axis_connection += test_connection(stepperX2);
#endif
TERN_(X_IS_TRINAMIC, axis_connection += test_connection(stepperX));
TERN_(X2_IS_TRINAMIC, axis_connection += test_connection(stepperX2));
}
if (TERN0(HAS_Y_AXIS, y)) {
#if AXIS_IS_TMC(Y)
axis_connection += test_connection(stepperY);
#endif
#if AXIS_IS_TMC(Y2)
axis_connection += test_connection(stepperY2);
#endif
TERN_(Y_IS_TRINAMIC, axis_connection += test_connection(stepperY));
TERN_(Y2_IS_TRINAMIC, axis_connection += test_connection(stepperY2));
}
if (TERN0(HAS_Z_AXIS, z)) {
#if AXIS_IS_TMC(Z)
axis_connection += test_connection(stepperZ);
#endif
#if AXIS_IS_TMC(Z2)
axis_connection += test_connection(stepperZ2);
#endif
#if AXIS_IS_TMC(Z3)
axis_connection += test_connection(stepperZ3);
#endif
#if AXIS_IS_TMC(Z4)
axis_connection += test_connection(stepperZ4);
#endif
TERN_(Z_IS_TRINAMIC, axis_connection += test_connection(stepperZ));
TERN_(Z2_IS_TRINAMIC, axis_connection += test_connection(stepperZ2));
TERN_(Z3_IS_TRINAMIC, axis_connection += test_connection(stepperZ3));
TERN_(Z4_IS_TRINAMIC, axis_connection += test_connection(stepperZ4));
}
#if AXIS_IS_TMC(I)
if (i) axis_connection += test_connection(stepperI);
#endif
#if AXIS_IS_TMC(J)
if (j) axis_connection += test_connection(stepperJ);
#endif
#if AXIS_IS_TMC(K)
if (k) axis_connection += test_connection(stepperK);
#endif
#if AXIS_IS_TMC(U)
if (u) axis_connection += test_connection(stepperU);
#endif
#if AXIS_IS_TMC(V)
if (v) axis_connection += test_connection(stepperV);
#endif
#if AXIS_IS_TMC(W)
if (w) axis_connection += test_connection(stepperW);
#endif
TERN_(I_IS_TRINAMIC, if (i) axis_connection += test_connection(stepperI));
TERN_(J_IS_TRINAMIC, if (j) axis_connection += test_connection(stepperJ));
TERN_(K_IS_TRINAMIC, if (k) axis_connection += test_connection(stepperK));
TERN_(U_IS_TRINAMIC, if (u) axis_connection += test_connection(stepperU));
TERN_(V_IS_TRINAMIC, if (v) axis_connection += test_connection(stepperV));
TERN_(W_IS_TRINAMIC, if (w) axis_connection += test_connection(stepperW));
if (TERN0(HAS_EXTRUDERS, e)) {
#if AXIS_IS_TMC(E0)
axis_connection += test_connection(stepperE0);
#endif
#if AXIS_IS_TMC(E1)
axis_connection += test_connection(stepperE1);
#endif
#if AXIS_IS_TMC(E2)
axis_connection += test_connection(stepperE2);
#endif
#if AXIS_IS_TMC(E3)
axis_connection += test_connection(stepperE3);
#endif
#if AXIS_IS_TMC(E4)
axis_connection += test_connection(stepperE4);
#endif
#if AXIS_IS_TMC(E5)
axis_connection += test_connection(stepperE5);
#endif
#if AXIS_IS_TMC(E6)
axis_connection += test_connection(stepperE6);
#endif
#if AXIS_IS_TMC(E7)
axis_connection += test_connection(stepperE7);
#endif
TERN_(E0_IS_TRINAMIC, axis_connection += test_connection(stepperE0));
TERN_(E1_IS_TRINAMIC, axis_connection += test_connection(stepperE1));
TERN_(E2_IS_TRINAMIC, axis_connection += test_connection(stepperE2));
TERN_(E3_IS_TRINAMIC, axis_connection += test_connection(stepperE3));
TERN_(E4_IS_TRINAMIC, axis_connection += test_connection(stepperE4));
TERN_(E5_IS_TRINAMIC, axis_connection += test_connection(stepperE5));
TERN_(E6_IS_TRINAMIC, axis_connection += test_connection(stepperE6));
TERN_(E7_IS_TRINAMIC, axis_connection += test_connection(stepperE7));
}
if (axis_connection) LCD_MESSAGE(MSG_ERROR_TMC);

View file

@ -375,6 +375,32 @@ void test_tmc_connection(LOGICAL_AXIS_DECL_LC(const bool, true));
#endif // USE_SENSORLESS
#if HAS_HOMING_CURRENT
// Axes that have a distinct homing current
struct homing_current_t {
OPTCODE(X_HAS_HOME_CURRENT, uint16_t X)
OPTCODE(Y_HAS_HOME_CURRENT, uint16_t Y)
OPTCODE(Z_HAS_HOME_CURRENT, uint16_t Z)
OPTCODE(X2_HAS_HOME_CURRENT, uint16_t X2)
OPTCODE(Y2_HAS_HOME_CURRENT, uint16_t Y2)
OPTCODE(Z2_HAS_HOME_CURRENT, uint16_t Z2)
OPTCODE(Z3_HAS_HOME_CURRENT, uint16_t Z3)
OPTCODE(Z4_HAS_HOME_CURRENT, uint16_t Z4)
OPTCODE(I_HAS_HOME_CURRENT, uint16_t I)
OPTCODE(J_HAS_HOME_CURRENT, uint16_t J)
OPTCODE(K_HAS_HOME_CURRENT, uint16_t K)
OPTCODE(U_HAS_HOME_CURRENT, uint16_t U)
OPTCODE(V_HAS_HOME_CURRENT, uint16_t V)
OPTCODE(W_HAS_HOME_CURRENT, uint16_t W)
};
#if ENABLED(EDITABLE_HOMING_CURRENT)
extern homing_current_t homing_current_mA;
#endif
#endif // HAS_HOMING_CURRENT
#endif // HAS_TRINAMIC_CONFIG
#if HAS_TMC_SPI

View file

@ -64,7 +64,7 @@ class TWIBus {
private:
/**
* @brief Number of bytes on buffer
* @description Number of bytes in the buffer waiting to be flushed to the bus
* @details Number of bytes in the buffer waiting to be flushed to the bus
*/
uint8_t buffer_s = 0;
@ -77,7 +77,7 @@ class TWIBus {
public:
/**
* @brief Target device address
* @description The target device address. Persists until changed.
* @details The target device address. Persists until changed.
*/
uint8_t addr = 0;

View file

@ -88,10 +88,8 @@
fr_mm_s = HYPOT(minfr, minfr);
// Set homing current to X and Y axis if defined
#if HAS_CURRENT_HOME(X)
set_homing_current(X_AXIS);
#endif
#if HAS_CURRENT_HOME(Y) && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
TERN_(X_HAS_HOME_CURRENT, set_homing_current(X_AXIS));
#if Y_HAS_HOME_CURRENT && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
set_homing_current(Y_AXIS);
#endif
@ -113,10 +111,8 @@
current_position.set(0.0, 0.0);
#if HAS_CURRENT_HOME(X)
restore_homing_current(X_AXIS);
#endif
#if HAS_CURRENT_HOME(Y) && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
TERN_(X_HAS_HOME_CURRENT, restore_homing_current(X_AXIS));
#if Y_HAS_HOME_CURRENT && NONE(CORE_IS_XY, MARKFORGED_XY, MARKFORGED_YX)
restore_homing_current(Y_AXIS);
#endif

View file

@ -95,37 +95,36 @@ void GcodeSuite::G34() {
#if HAS_MOTOR_CURRENT_SPI
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
const uint32_t previous_current = stepper.motor_current_setting[Z_AXIS];
const uint32_t previous_current_Z = stepper.motor_current_setting[Z_AXIS];
stepper.set_digipot_current(Z_AXIS, target_current);
#elif HAS_MOTOR_CURRENT_PWM
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
const uint32_t previous_current = stepper.motor_current_setting[1]; // Z
const uint32_t previous_current_Z = stepper.motor_current_setting[1]; // Z
stepper.set_digipot_current(1, target_current);
#elif HAS_MOTOR_CURRENT_DAC
const float target_current = parser.floatval('S', GANTRY_CALIBRATION_CURRENT);
const float previous_current = dac_amps(Z_AXIS, target_current);
const float previous_current_Z = dac_amps(Z_AXIS, target_current);
stepper_dac.set_current_value(Z_AXIS, target_current);
#elif HAS_MOTOR_CURRENT_I2C
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
previous_current = dac_amps(Z_AXIS);
const float previous_current_Z = dac_amps(Z_AXIS);
digipot_i2c.set_current(Z_AXIS, target_current)
#elif HAS_TRINAMIC_CONFIG
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
static uint16_t previous_current_arr[NUM_Z_STEPPERS];
#if AXIS_IS_TMC(Z)
previous_current_arr[0] = stepperZ.getMilliamps();
#if Z_IS_TRINAMIC
static uint16_t previous_current_Z = stepperZ.getMilliamps();
stepperZ.rms_current(target_current);
#endif
#if AXIS_IS_TMC(Z2)
previous_current_arr[1] = stepperZ2.getMilliamps();
#if Z2_IS_TRINAMIC
static uint16_t previous_current_Z2 = stepperZ2.getMilliamps();
stepperZ2.rms_current(target_current);
#endif
#if AXIS_IS_TMC(Z3)
previous_current_arr[2] = stepperZ3.getMilliamps();
#if Z3_IS_TRINAMIC
static uint16_t previous_current_Z3 = stepperZ3.getMilliamps();
stepperZ3.rms_current(target_current);
#endif
#if AXIS_IS_TMC(Z4)
previous_current_arr[3] = stepperZ4.getMilliamps();
#if Z4_IS_TRINAMIC
static uint16_t previous_current_Z4 = stepperZ4.getMilliamps();
stepperZ4.rms_current(target_current);
#endif
#endif
@ -140,26 +139,18 @@ void GcodeSuite::G34() {
#endif
#if HAS_MOTOR_CURRENT_SPI
stepper.set_digipot_current(Z_AXIS, previous_current);
stepper.set_digipot_current(Z_AXIS, previous_current_Z);
#elif HAS_MOTOR_CURRENT_PWM
stepper.set_digipot_current(1, previous_current);
stepper.set_digipot_current(1, previous_current_Z);
#elif HAS_MOTOR_CURRENT_DAC
stepper_dac.set_current_value(Z_AXIS, previous_current);
stepper_dac.set_current_value(Z_AXIS, previous_current_Z);
#elif HAS_MOTOR_CURRENT_I2C
digipot_i2c.set_current(Z_AXIS, previous_current)
digipot_i2c.set_current(Z_AXIS, previous_current_Z)
#elif HAS_TRINAMIC_CONFIG
#if AXIS_IS_TMC(Z)
stepperZ.rms_current(previous_current_arr[0]);
#endif
#if AXIS_IS_TMC(Z2)
stepperZ2.rms_current(previous_current_arr[1]);
#endif
#if AXIS_IS_TMC(Z3)
stepperZ3.rms_current(previous_current_arr[2]);
#endif
#if AXIS_IS_TMC(Z4)
stepperZ4.rms_current(previous_current_arr[3]);
#endif
TERN_(Z_IS_TRINAMIC, stepperZ.rms_current(previous_current_Z));
TERN_(Z2_IS_TRINAMIC, stepperZ2.rms_current(previous_current_Z2));
TERN_(Z3_IS_TRINAMIC, stepperZ3.rms_current(previous_current_Z3));
TERN_(Z4_IS_TRINAMIC, stepperZ4.rms_current(previous_current_Z4));
#endif
// Back off end plate, back to normal motion range

View file

@ -0,0 +1,59 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../inc/MarlinConfig.h"
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
#include "../gcode.h"
#include "../../MarlinCore.h"
#include "../../lcd/marlinui.h"
/**
* M550: Set machine name
*
* Parameters:
* P "<name>" Set the name using the 'P' parameter (RepRapFirmware)
* "<name>" Set the name using the "string" parameter
*/
void GcodeSuite::M550() {
bool did_set = true;
if (parser.seenval('P'))
machine_name = parser.value_string();
else if (TERN(GCODE_QUOTED_STRINGS, false, parser.seen('P')))
machine_name = parser.string_arg[0] == 'P' ? &parser.string_arg[1] : parser.string_arg;
else if (parser.string_arg && parser.string_arg[0])
machine_name = parser.string_arg;
else
did_set = false;
if (did_set) {
machine_name.trim();
ui.reset_status(false);
}
else
SERIAL_ECHOLNPGM("RepRap name: ", &machine_name);
}
#endif // CONFIGURABLE_MACHINE_NAME

View file

@ -38,7 +38,7 @@
#include "../../feature/powerloss.h"
#endif
#if HAS_SUICIDE
#if ANY(HAS_SUICIDE, CONFIGURABLE_MACHINE_NAME)
#include "../../MarlinCore.h"
#endif
@ -92,7 +92,11 @@ void GcodeSuite::M81() {
safe_delay(1000); // Wait 1 second before switching off
LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF ".");
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
ui.set_status(&MString<30>(&machine_name, ' ', F(STR_OFF), '.'));
#else
LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF ".");
#endif
bool delayed_power_off = false;

View file

@ -46,15 +46,32 @@
* Set percentage of max current for all axes (Requires HAS_DIGIPOT_DAC)
*/
void GcodeSuite::M907() {
#if HAS_MOTOR_CURRENT_SPI
if (!parser.seen("BS" STR_AXES_LOGICAL))
return M907_report();
if (parser.seenval('S')) for (uint8_t i = 0; i < MOTOR_CURRENT_COUNT; ++i) stepper.set_digipot_current(i, parser.value_int());
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int()); // X Y Z (I J K U V W) E (map to drivers according to DIGIPOT_CHANNELS. Default with NUM_AXES 3: map X Y Z E to X Y Z E0)
// Additional extruders use B,C.
// TODO: Change these parameters because 'E' is used and D should be reserved for debugging. B<index>?
// S<current> - Set current in mA for all axes
if (parser.seenval('S'))
for (uint8_t i = 0; i < MOTOR_CURRENT_COUNT; ++i)
stepper.set_digipot_current(i, parser.value_int());
// X Y Z I J K U V W E
// Map to drivers according to pots addresses.
// Default with NUM_AXES 3: map X Y Z E to X Y Z E0.
LOOP_LOGICAL_AXES(i)
if (parser.seenval(IAXIS_CHAR(i)))
stepper.set_digipot_current(i, parser.value_int());
/**
* Additional extruders use B,C in this legacy protocol
* TODO: Update to allow for an index with X, Y, Z, E axis to isolate a single stepper
* and use configured axis names instead of IJKUVW. i.e., Match the behavior of
* other G-codes that set stepper-specific parameters. If necessary deprecate G-codes.
* Bonus Points: Standardize a method that all G-codes can use to refer to one or
* more steppers/drivers and apply to various G-codes.
*/
#if E_STEPPERS >= 2
if (parser.seenval('B')) stepper.set_digipot_current(E_AXIS + 1, parser.value_int());
#if E_STEPPERS >= 3
@ -68,58 +85,88 @@ void GcodeSuite::M907() {
#define HAS_X_Y_XY_I_J_K_U_V_W 1
#endif
#if HAS_X_Y_XY_I_J_K_U_V_W || HAS_MOTOR_CURRENT_PWM_E || PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#if ANY(HAS_X_Y_XY_I_J_K_U_V_W, HAS_MOTOR_CURRENT_PWM_E, HAS_MOTOR_CURRENT_PWM_Z)
if (!parser.seen("S"
#if HAS_X_Y_XY_I_J_K_U_V_W
"XY" SECONDARY_AXIS_GANG("I", "J", "K", "U", "V", "W")
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
"Z"
#endif
#if HAS_MOTOR_CURRENT_PWM_E
"E"
NUM_AXIS_GANG("X", "Y",, "I", "J", "K", "U", "V", "W")
#endif
TERN_(HAS_MOTOR_CURRENT_PWM_Z, "Z")
TERN_(HAS_MOTOR_CURRENT_PWM_E, "E")
)) return M907_report();
if (parser.seenval('S')) for (uint8_t a = 0; a < MOTOR_CURRENT_COUNT; ++a) stepper.set_digipot_current(a, parser.value_int());
// S<current> - Set all stepper current to the same value
if (parser.seenval('S')) {
const int16_t v = parser.value_int();
for (uint8_t a = 0; a < MOTOR_CURRENT_COUNT; ++a)
stepper.set_digipot_current(a, v);
}
#if HAS_X_Y_XY_I_J_K_U_V_W
if (NUM_AXIS_GANG(
parser.seenval('X'), || parser.seenval('Y'), || false,
|| parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'),
|| parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W')
)) stepper.set_digipot_current(0, parser.value_int());
#endif
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
if (parser.seenval('Z')) stepper.set_digipot_current(1, parser.value_int());
#endif
#if HAS_MOTOR_CURRENT_PWM_E
if (parser.seenval('E')) stepper.set_digipot_current(2, parser.value_int());
#endif
// X Y I J K U V W - All aliases to set the current for "most axes."
// Only the value of the last given parameter is used.
if (ENABLED(HAS_X_Y_XY_I_J_K_U_V_W) && NUM_AXIS_GANG(
parser.seenval('X'), || parser.seenval('Y'), || false,
|| parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'),
|| parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W')
))
stepper.set_digipot_current(0, parser.value_int());
// Z<current> - Set the current just for the Z axis
if (TERN0(HAS_MOTOR_CURRENT_PWM_Z, parser.seenval('Z')))
stepper.set_digipot_current(1, parser.value_int());
// Z<current> - Set the current just for the Extruder
if (TERN0(HAS_MOTOR_CURRENT_PWM_E, parser.seenval('E')))
stepper.set_digipot_current(2, parser.value_int());
#endif
#endif // HAS_MOTOR_CURRENT_PWM
#if HAS_MOTOR_CURRENT_I2C
// this one uses actual amps in floating point
if (parser.seenval('S')) for (uint8_t q = 0; q < DIGIPOT_I2C_NUM_CHANNELS; ++q) digipot_i2c.set_current(q, parser.value_float());
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to pots adresses. Default with NUM_AXES 3 X Y Z E: map to X Y Z E0)
// This current driver takes actual Amps in floating point
// rather than milli-amps or some scalar unit.
// S<current> - Set the same current in Amps on all channels
if (parser.seenval('S')) {
const float v = parser.value_float();
for (uint8_t q = 0; q < DIGIPOT_I2C_NUM_CHANNELS; ++q)
digipot_i2c.set_current(q, v);
}
// X Y Z I J K U V W E
// Map to drivers according to pots addresses.
// Default with NUM_AXES 3: map X Y Z E to X Y Z E0.
LOOP_LOGICAL_AXES(i)
if (parser.seenval(IAXIS_CHAR(i)))
digipot_i2c.set_current(i, parser.value_float());
// Additional extruders use B,C,D.
// TODO: Change these parameters because 'E' is used and because 'D' should be reserved for debugging. B<index>?
// TODO: Make parameters work like other axis-specific / stepper-specific. See above.
#if E_STEPPERS >= 2
for (uint8_t i = E_AXIS + 1; i < _MAX(DIGIPOT_I2C_NUM_CHANNELS, (NUM_AXES + 3)); i++)
if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float());
if (parser.seenval('B' + i - (E_AXIS + 1)))
digipot_i2c.set_current(i, parser.value_float());
#endif
#endif
#endif // HAS_MOTOR_CURRENT_I2C
#if HAS_MOTOR_CURRENT_DAC
// S<current> - Set the same current percentage on all axes
if (parser.seenval('S')) {
const float dac_percent = parser.value_float();
LOOP_LOGICAL_AXES(i) stepper_dac.set_current_percent(i, dac_percent);
LOOP_LOGICAL_AXES(i)
stepper_dac.set_current_percent(i, dac_percent);
}
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper_dac.set_current_percent(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to DAC_STEPPER_ORDER. Default with NUM_AXES 3: X Y Z E map to X Y Z E0)
// X Y Z I J K U V W E
// Map to drivers according to pots addresses.
// Default with NUM_AXES 3: map X Y Z E to X Y Z E0.
LOOP_LOGICAL_AXES(i)
if (parser.seenval(IAXIS_CHAR(i)))
stepper_dac.set_current_percent(i, parser.value_float());
#endif
}
@ -131,8 +178,10 @@ void GcodeSuite::M907() {
report_heading_etc(forReplay, F(STR_STEPPER_MOTOR_CURRENTS));
#if HAS_MOTOR_CURRENT_PWM
SERIAL_ECHOLNPGM_P( // PWM-based has 3 values:
PSTR(" M907 X"), stepper.motor_current_setting[0] // X, Y, (I, J, K, U, V, W)
, SP_Z_STR, stepper.motor_current_setting[1] // Z
PSTR(" M907 X"), stepper.motor_current_setting[0] // X, Y, (I, J, K, U, V, W)
#if HAS_MOTOR_CURRENT_PWM_Z
, SP_Z_STR, stepper.motor_current_setting[1] // Z
#endif
#if HAS_MOTOR_CURRENT_PWM_E
, SP_E_STR, stepper.motor_current_setting[2] // E
#endif

View file

@ -37,6 +37,8 @@ static void tmc_print_current(TMC &st) {
/**
* M906: Set motor current in milliamps.
*
* With no parameters report driver currents.
*
* Parameters:
* X[current] - Set mA current for X driver(s)
* Y[current] - Set mA current for Y driver(s)
@ -52,181 +54,109 @@ static void tmc_print_current(TMC &st) {
* I[index] - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4.)
* T[index] - Extruder index (Zero-based. Omit for E0 only.)
*
* With no parameters report driver currents.
* With EDITABLE_HOMING_CURRENT:
* H - Set / Report Homing Current. Alias for M920.
*/
void GcodeSuite::M906() {
#if ENABLED(EDITABLE_HOMING_CURRENT)
if (parser.seen_test('H')) return M920();
#endif
#define TMC_SAY_CURRENT(Q) tmc_print_current(stepper##Q)
#define TMC_SET_CURRENT(Q) stepper##Q.rms_current(value)
bool report = true;
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
#if ANY(X2_IS_TRINAMIC, Y2_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
const int8_t index = parser.byteval('I', -1);
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
#elif ANY(X_IS_TRINAMIC, Y_IS_TRINAMIC, Z_IS_TRINAMIC)
constexpr int8_t index = -1;
#endif
LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(AXIS_CHAR(i))) {
report = false;
switch (i) {
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2)
#if X_IS_TRINAMIC || X2_IS_TRINAMIC
case X_AXIS:
#if AXIS_IS_TMC(X)
if (index < 0 || index == 0) TMC_SET_CURRENT(X);
#endif
#if AXIS_IS_TMC(X2)
if (index < 0 || index == 1) TMC_SET_CURRENT(X2);
#endif
TERN_(X_IS_TRINAMIC, if (index < 0 || index == 0) TMC_SET_CURRENT(X));
TERN_(X2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CURRENT(X2));
break;
#endif
#if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2)
#if Y_IS_TRINAMIC || Y2_IS_TRINAMIC
case Y_AXIS:
#if AXIS_IS_TMC(Y)
if (index < 0 || index == 0) TMC_SET_CURRENT(Y);
#endif
#if AXIS_IS_TMC(Y2)
if (index < 0 || index == 1) TMC_SET_CURRENT(Y2);
#endif
TERN_(Y_IS_TRINAMIC, if (index < 0 || index == 0) TMC_SET_CURRENT(Y));
TERN_(Y2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CURRENT(Y2));
break;
#endif
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
#if ANY(Z_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
case Z_AXIS:
#if AXIS_IS_TMC(Z)
if (index < 0 || index == 0) TMC_SET_CURRENT(Z);
#endif
#if AXIS_IS_TMC(Z2)
if (index < 0 || index == 1) TMC_SET_CURRENT(Z2);
#endif
#if AXIS_IS_TMC(Z3)
if (index < 0 || index == 2) TMC_SET_CURRENT(Z3);
#endif
#if AXIS_IS_TMC(Z4)
if (index < 0 || index == 3) TMC_SET_CURRENT(Z4);
#endif
TERN_(Z_IS_TRINAMIC, if (index < 0 || index == 0) TMC_SET_CURRENT(Z));
TERN_(Z2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CURRENT(Z2));
TERN_(Z3_IS_TRINAMIC, if (index < 0 || index == 2) TMC_SET_CURRENT(Z3));
TERN_(Z4_IS_TRINAMIC, if (index < 0 || index == 3) TMC_SET_CURRENT(Z4));
break;
#endif
#if AXIS_IS_TMC(I)
#if I_IS_TRINAMIC
case I_AXIS: TMC_SET_CURRENT(I); break;
#endif
#if AXIS_IS_TMC(J)
#if J_IS_TRINAMIC
case J_AXIS: TMC_SET_CURRENT(J); break;
#endif
#if AXIS_IS_TMC(K)
#if K_IS_TRINAMIC
case K_AXIS: TMC_SET_CURRENT(K); break;
#endif
#if AXIS_IS_TMC(U)
#if U_IS_TRINAMIC
case U_AXIS: TMC_SET_CURRENT(U); break;
#endif
#if AXIS_IS_TMC(V)
#if V_IS_TRINAMIC
case V_AXIS: TMC_SET_CURRENT(V); break;
#endif
#if AXIS_IS_TMC(W)
#if W_IS_TRINAMIC
case W_AXIS: TMC_SET_CURRENT(W); break;
#endif
#if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7)
#if ANY(E0_IS_TRINAMIC, E1_IS_TRINAMIC, E2_IS_TRINAMIC, E3_IS_TRINAMIC, E4_IS_TRINAMIC, E5_IS_TRINAMIC, E6_IS_TRINAMIC, E7_IS_TRINAMIC)
case E_AXIS: {
const int8_t eindex = get_target_e_stepper_from_command(-2);
#if AXIS_IS_TMC(E0)
if (eindex < 0 || eindex == 0) TMC_SET_CURRENT(E0);
#endif
#if AXIS_IS_TMC(E1)
if (eindex < 0 || eindex == 1) TMC_SET_CURRENT(E1);
#endif
#if AXIS_IS_TMC(E2)
if (eindex < 0 || eindex == 2) TMC_SET_CURRENT(E2);
#endif
#if AXIS_IS_TMC(E3)
if (eindex < 0 || eindex == 3) TMC_SET_CURRENT(E3);
#endif
#if AXIS_IS_TMC(E4)
if (eindex < 0 || eindex == 4) TMC_SET_CURRENT(E4);
#endif
#if AXIS_IS_TMC(E5)
if (eindex < 0 || eindex == 5) TMC_SET_CURRENT(E5);
#endif
#if AXIS_IS_TMC(E6)
if (eindex < 0 || eindex == 6) TMC_SET_CURRENT(E6);
#endif
#if AXIS_IS_TMC(E7)
if (eindex < 0 || eindex == 7) TMC_SET_CURRENT(E7);
#endif
TERN_(E0_IS_TRINAMIC, if (eindex < 0 || eindex == 0) TMC_SET_CURRENT(E0));
TERN_(E1_IS_TRINAMIC, if (eindex < 0 || eindex == 1) TMC_SET_CURRENT(E1));
TERN_(E2_IS_TRINAMIC, if (eindex < 0 || eindex == 2) TMC_SET_CURRENT(E2));
TERN_(E3_IS_TRINAMIC, if (eindex < 0 || eindex == 3) TMC_SET_CURRENT(E3));
TERN_(E4_IS_TRINAMIC, if (eindex < 0 || eindex == 4) TMC_SET_CURRENT(E4));
TERN_(E5_IS_TRINAMIC, if (eindex < 0 || eindex == 5) TMC_SET_CURRENT(E5));
TERN_(E6_IS_TRINAMIC, if (eindex < 0 || eindex == 6) TMC_SET_CURRENT(E6));
TERN_(E7_IS_TRINAMIC, if (eindex < 0 || eindex == 7) TMC_SET_CURRENT(E7));
} break;
#endif
}
}
if (report) {
#if AXIS_IS_TMC(X)
TMC_SAY_CURRENT(X);
#endif
#if AXIS_IS_TMC(X2)
TMC_SAY_CURRENT(X2);
#endif
#if AXIS_IS_TMC(Y)
TMC_SAY_CURRENT(Y);
#endif
#if AXIS_IS_TMC(Y2)
TMC_SAY_CURRENT(Y2);
#endif
#if AXIS_IS_TMC(Z)
TMC_SAY_CURRENT(Z);
#endif
#if AXIS_IS_TMC(Z2)
TMC_SAY_CURRENT(Z2);
#endif
#if AXIS_IS_TMC(Z3)
TMC_SAY_CURRENT(Z3);
#endif
#if AXIS_IS_TMC(Z4)
TMC_SAY_CURRENT(Z4);
#endif
#if AXIS_IS_TMC(I)
TMC_SAY_CURRENT(I);
#endif
#if AXIS_IS_TMC(J)
TMC_SAY_CURRENT(J);
#endif
#if AXIS_IS_TMC(K)
TMC_SAY_CURRENT(K);
#endif
#if AXIS_IS_TMC(U)
TMC_SAY_CURRENT(U);
#endif
#if AXIS_IS_TMC(V)
TMC_SAY_CURRENT(V);
#endif
#if AXIS_IS_TMC(W)
TMC_SAY_CURRENT(W);
#endif
#if AXIS_IS_TMC(E0)
TMC_SAY_CURRENT(E0);
#endif
#if AXIS_IS_TMC(E1)
TMC_SAY_CURRENT(E1);
#endif
#if AXIS_IS_TMC(E2)
TMC_SAY_CURRENT(E2);
#endif
#if AXIS_IS_TMC(E3)
TMC_SAY_CURRENT(E3);
#endif
#if AXIS_IS_TMC(E4)
TMC_SAY_CURRENT(E4);
#endif
#if AXIS_IS_TMC(E5)
TMC_SAY_CURRENT(E5);
#endif
#if AXIS_IS_TMC(E6)
TMC_SAY_CURRENT(E6);
#endif
#if AXIS_IS_TMC(E7)
TMC_SAY_CURRENT(E7);
#endif
TERN_(X_IS_TRINAMIC, TMC_SAY_CURRENT(X));
TERN_(X2_IS_TRINAMIC, TMC_SAY_CURRENT(X2));
TERN_(Y_IS_TRINAMIC, TMC_SAY_CURRENT(Y));
TERN_(Y2_IS_TRINAMIC, TMC_SAY_CURRENT(Y2));
TERN_(Z_IS_TRINAMIC, TMC_SAY_CURRENT(Z));
TERN_(Z2_IS_TRINAMIC, TMC_SAY_CURRENT(Z2));
TERN_(Z3_IS_TRINAMIC, TMC_SAY_CURRENT(Z3));
TERN_(Z4_IS_TRINAMIC, TMC_SAY_CURRENT(Z4));
TERN_(I_IS_TRINAMIC, TMC_SAY_CURRENT(I));
TERN_(J_IS_TRINAMIC, TMC_SAY_CURRENT(J));
TERN_(K_IS_TRINAMIC, TMC_SAY_CURRENT(K));
TERN_(U_IS_TRINAMIC, TMC_SAY_CURRENT(U));
TERN_(V_IS_TRINAMIC, TMC_SAY_CURRENT(V));
TERN_(W_IS_TRINAMIC, TMC_SAY_CURRENT(W));
TERN_(E0_IS_TRINAMIC, TMC_SAY_CURRENT(E0));
TERN_(E1_IS_TRINAMIC, TMC_SAY_CURRENT(E1));
TERN_(E2_IS_TRINAMIC, TMC_SAY_CURRENT(E2));
TERN_(E3_IS_TRINAMIC, TMC_SAY_CURRENT(E3));
TERN_(E4_IS_TRINAMIC, TMC_SAY_CURRENT(E4));
TERN_(E5_IS_TRINAMIC, TMC_SAY_CURRENT(E5));
TERN_(E6_IS_TRINAMIC, TMC_SAY_CURRENT(E6));
TERN_(E7_IS_TRINAMIC, TMC_SAY_CURRENT(E7));
}
}
@ -240,93 +170,67 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
SERIAL_ECHOPGM(" M906");
};
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) \
|| AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) \
|| AXIS_IS_TMC(U) || AXIS_IS_TMC(V) || AXIS_IS_TMC(W)
#if ANY(X_IS_TRINAMIC, Y_IS_TRINAMIC, Z_IS_TRINAMIC, I_IS_TRINAMIC, J_IS_TRINAMIC, K_IS_TRINAMIC, U_IS_TRINAMIC, V_IS_TRINAMIC, W_IS_TRINAMIC)
say_M906(forReplay);
#if AXIS_IS_TMC(X)
SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps());
#endif
#if AXIS_IS_TMC(Y)
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.getMilliamps());
#endif
#if AXIS_IS_TMC(Z)
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.getMilliamps());
#endif
#if AXIS_IS_TMC(I)
SERIAL_ECHOPGM_P(SP_I_STR, stepperI.getMilliamps());
#endif
#if AXIS_IS_TMC(J)
SERIAL_ECHOPGM_P(SP_J_STR, stepperJ.getMilliamps());
#endif
#if AXIS_IS_TMC(K)
SERIAL_ECHOPGM_P(SP_K_STR, stepperK.getMilliamps());
#endif
#if AXIS_IS_TMC(U)
SERIAL_ECHOPGM_P(SP_U_STR, stepperU.getMilliamps());
#endif
#if AXIS_IS_TMC(V)
SERIAL_ECHOPGM_P(SP_V_STR, stepperV.getMilliamps());
#endif
#if AXIS_IS_TMC(W)
SERIAL_ECHOPGM_P(SP_W_STR, stepperW.getMilliamps());
#endif
TERN_(X_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps()));
TERN_(Y_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.getMilliamps()));
TERN_(Z_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.getMilliamps()));
TERN_(I_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_I_STR, stepperI.getMilliamps()));
TERN_(J_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_J_STR, stepperJ.getMilliamps()));
TERN_(K_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_K_STR, stepperK.getMilliamps()));
TERN_(U_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_U_STR, stepperU.getMilliamps()));
TERN_(V_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_V_STR, stepperV.getMilliamps()));
TERN_(W_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_W_STR, stepperW.getMilliamps()));
SERIAL_EOL();
#endif
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
#if X2_IS_TRINAMIC || Y2_IS_TRINAMIC || Z2_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOPGM(" I1");
#if AXIS_IS_TMC(X2)
SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.getMilliamps());
#endif
#if AXIS_IS_TMC(Y2)
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.getMilliamps());
#endif
#if AXIS_IS_TMC(Z2)
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.getMilliamps());
#endif
TERN_(X2_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.getMilliamps()));
TERN_(Y2_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.getMilliamps()));
TERN_(Z2_IS_TRINAMIC, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.getMilliamps()));
SERIAL_EOL();
#endif
#if AXIS_IS_TMC(Z3)
#if Z3_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.getMilliamps());
#endif
#if AXIS_IS_TMC(Z4)
#if Z4_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.getMilliamps());
#endif
#if AXIS_IS_TMC(E0)
#if E0_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T0 E", stepperE0.getMilliamps());
#endif
#if AXIS_IS_TMC(E1)
#if E1_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T1 E", stepperE1.getMilliamps());
#endif
#if AXIS_IS_TMC(E2)
#if E2_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T2 E", stepperE2.getMilliamps());
#endif
#if AXIS_IS_TMC(E3)
#if E3_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T3 E", stepperE3.getMilliamps());
#endif
#if AXIS_IS_TMC(E4)
#if E4_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T4 E", stepperE4.getMilliamps());
#endif
#if AXIS_IS_TMC(E5)
#if E5_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T5 E", stepperE5.getMilliamps());
#endif
#if AXIS_IS_TMC(E6)
#if E6_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T6 E", stepperE6.getMilliamps());
#endif
#if AXIS_IS_TMC(E7)
#if E7_IS_TRINAMIC
say_M906(forReplay);
SERIAL_ECHOLNPGM(" T7 E", stepperE7.getMilliamps());
#endif

View file

@ -274,7 +274,23 @@
}
/**
* M913: Set HYBRID_THRESHOLD speed.
* M913: Set HYBRID_THRESHOLD speed, aka PWM Threshold.
*
* Parameters:
* I<num> - For multi-stepper axes, the one-based index of the stepper to modify in each set
*
* E<value> - Set threshold for one or more Extruders
* T<index> - The zero-based index of the Extruder to modify
*
* X<value> - Set threshold for one or more X axis steppers
* Y<value> - Set threshold for one or more Y axis steppers
* Z<value> - Set threshold for one or more Z axis steppers
* A<value> - Set threshold for one or more A axis steppers
* B<value> - Set threshold for one or more B axis steppers
* C<value> - Set threshold for one or more C axis steppers
* U<value> - Set threshold for one or more U axis steppers
* V<value> - Set threshold for one or more V axis steppers
* W<value> - Set threshold for one or more W axis steppers
*/
void GcodeSuite::M913() {
#define TMC_SAY_PWMTHRS(A,Q) tmc_print_pwmthrs(stepper##Q)
@ -283,9 +299,9 @@
#define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
bool report = true;
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
#if ANY(X2_IS_TRINAMIC, Y2_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
const uint8_t index = parser.byteval('I');
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
#elif ANY(X_IS_TRINAMIC, Y_IS_TRINAMIC, Z_IS_TRINAMIC)
constexpr uint8_t index = 0;
#endif
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(AXIS_CHAR(i))) {
@ -387,70 +403,37 @@
SERIAL_ECHOPGM(" M913");
};
#if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP
#if ANY(X_HAS_STEALTHCHOP, Y_HAS_STEALTHCHOP, Z_HAS_STEALTHCHOP, I_HAS_STEALTHCHOP, J_HAS_STEALTHCHOP, K_HAS_STEALTHCHOP, U_HAS_STEALTHCHOP, V_HAS_STEALTHCHOP, W_HAS_STEALTHCHOP)
say_M913(forReplay);
#if X_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_X_STR, stepperX.get_pwm_thrs());
#endif
#if Y_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.get_pwm_thrs());
#endif
#if Z_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.get_pwm_thrs());
#endif
TERN_(X_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_X_STR, stepperX.get_pwm_thrs()));
TERN_(Y_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.get_pwm_thrs()));
TERN_(Z_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.get_pwm_thrs()));
TERN_(I_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_I_STR, stepperI.get_pwm_thrs()));
TERN_(J_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_J_STR, stepperJ.get_pwm_thrs()));
TERN_(K_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_K_STR, stepperK.get_pwm_thrs()));
TERN_(U_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_U_STR, stepperU.get_pwm_thrs()));
TERN_(V_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_V_STR, stepperV.get_pwm_thrs()));
TERN_(W_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_W_STR, stepperW.get_pwm_thrs()));
SERIAL_EOL();
#endif
#if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOPGM(" I2");
#if X2_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.get_pwm_thrs());
#endif
#if Y2_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.get_pwm_thrs());
#endif
#if Z2_HAS_STEALTHCHOP
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.get_pwm_thrs());
#endif
TERN_(X2_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.get_pwm_thrs()));
TERN_(Y2_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.get_pwm_thrs()));
TERN_(Z2_HAS_STEALTHCHOP, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.get_pwm_thrs()));
SERIAL_EOL();
#endif
#if Z3_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM(" I3 Z", stepperZ3.get_pwm_thrs());
#endif
#if Z4_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM(" I4 Z", stepperZ4.get_pwm_thrs());
#endif
#if I_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.get_pwm_thrs());
#endif
#if J_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.get_pwm_thrs());
#endif
#if K_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.get_pwm_thrs());
#endif
#if U_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.get_pwm_thrs());
#endif
#if V_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.get_pwm_thrs());
#endif
#if W_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.get_pwm_thrs());
#endif
#if E0_HAS_STEALTHCHOP
say_M913(forReplay);
SERIAL_ECHOLNPGM(" T0 E", stepperE0.get_pwm_thrs());
@ -498,7 +481,19 @@
}
/**
* M914: Set StallGuard sensitivity.
* M914: Set StallGuard sensitivity in terms of "homing threshold" (not for stall detection during printing).
*
* Parameters:
* I<num> - For multi-stepper axes, the one-based index of the stepper to modify in each set
* X<value> - Set threshold for one or more X axis steppers
* Y<value> - Set threshold for one or more Y axis steppers
* Z<value> - Set threshold for one or more Z axis steppers
* A<value> - Set threshold for one or more A axis steppers
* B<value> - Set threshold for one or more B axis steppers
* C<value> - Set threshold for one or more C axis steppers
* U<value> - Set threshold for one or more U axis steppers
* V<value> - Set threshold for one or more V axis steppers
* W<value> - Set threshold for one or more W axis steppers
*/
void GcodeSuite::M914() {
bool report = true;
@ -536,33 +531,33 @@
#if K_SENSORLESS
case K_AXIS: stepperK.homing_threshold(value); break;
#endif
#if U_SENSORLESS && AXIS_HAS_STALLGUARD(U)
#if U_SENSORLESS
case U_AXIS: stepperU.homing_threshold(value); break;
#endif
#if V_SENSORLESS && AXIS_HAS_STALLGUARD(V)
#if V_SENSORLESS
case V_AXIS: stepperV.homing_threshold(value); break;
#endif
#if W_SENSORLESS && AXIS_HAS_STALLGUARD(W)
#if W_SENSORLESS
case W_AXIS: stepperW.homing_threshold(value); break;
#endif
}
}
if (report) {
TERN_(X_SENSORLESS, tmc_print_sgt(stepperX));
TERN_( X_SENSORLESS, tmc_print_sgt(stepperX));
TERN_(X2_SENSORLESS, tmc_print_sgt(stepperX2));
TERN_(Y_SENSORLESS, tmc_print_sgt(stepperY));
TERN_( Y_SENSORLESS, tmc_print_sgt(stepperY));
TERN_(Y2_SENSORLESS, tmc_print_sgt(stepperY2));
TERN_(Z_SENSORLESS, tmc_print_sgt(stepperZ));
TERN_( Z_SENSORLESS, tmc_print_sgt(stepperZ));
TERN_(Z2_SENSORLESS, tmc_print_sgt(stepperZ2));
TERN_(Z3_SENSORLESS, tmc_print_sgt(stepperZ3));
TERN_(Z4_SENSORLESS, tmc_print_sgt(stepperZ4));
TERN_(I_SENSORLESS, tmc_print_sgt(stepperI));
TERN_(J_SENSORLESS, tmc_print_sgt(stepperJ));
TERN_(K_SENSORLESS, tmc_print_sgt(stepperK));
TERN_(U_SENSORLESS, tmc_print_sgt(stepperU));
TERN_(V_SENSORLESS, tmc_print_sgt(stepperV));
TERN_(W_SENSORLESS, tmc_print_sgt(stepperW));
TERN_( I_SENSORLESS, tmc_print_sgt(stepperI));
TERN_( J_SENSORLESS, tmc_print_sgt(stepperJ));
TERN_( K_SENSORLESS, tmc_print_sgt(stepperK));
TERN_( U_SENSORLESS, tmc_print_sgt(stepperU));
TERN_( V_SENSORLESS, tmc_print_sgt(stepperV));
TERN_( W_SENSORLESS, tmc_print_sgt(stepperW));
}
}
@ -578,67 +573,34 @@
#if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS
say_M914(forReplay);
#if X_SENSORLESS
SERIAL_ECHOPGM_P(SP_X_STR, stepperX.homing_threshold());
#endif
#if Y_SENSORLESS
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.homing_threshold());
#endif
#if Z_SENSORLESS
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.homing_threshold());
#endif
TERN_(X_SENSORLESS, SERIAL_ECHOPGM_P(SP_X_STR, stepperX.homing_threshold()));
TERN_(Y_SENSORLESS, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY.homing_threshold()));
TERN_(Z_SENSORLESS, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ.homing_threshold()));
TERN_(I_SENSORLESS, SERIAL_ECHOPGM_P(SP_I_STR, stepperI.homing_threshold()));
TERN_(J_SENSORLESS, SERIAL_ECHOPGM_P(SP_J_STR, stepperJ.homing_threshold()));
TERN_(K_SENSORLESS, SERIAL_ECHOPGM_P(SP_K_STR, stepperK.homing_threshold()));
TERN_(U_SENSORLESS, SERIAL_ECHOPGM_P(SP_U_STR, stepperU.homing_threshold()));
TERN_(V_SENSORLESS, SERIAL_ECHOPGM_P(SP_V_STR, stepperV.homing_threshold()));
TERN_(W_SENSORLESS, SERIAL_ECHOPGM_P(SP_W_STR, stepperW.homing_threshold()));
SERIAL_EOL();
#endif
#if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOPGM(" I2");
#if X2_SENSORLESS
SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.homing_threshold());
#endif
#if Y2_SENSORLESS
SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.homing_threshold());
#endif
#if Z2_SENSORLESS
SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.homing_threshold());
#endif
TERN_(X2_SENSORLESS, SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.homing_threshold()));
TERN_(Y2_SENSORLESS, SERIAL_ECHOPGM_P(SP_Y_STR, stepperY2.homing_threshold()));
TERN_(Z2_SENSORLESS, SERIAL_ECHOPGM_P(SP_Z_STR, stepperZ2.homing_threshold()));
SERIAL_EOL();
#endif
#if Z3_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM(" I3 Z", stepperZ3.homing_threshold());
#endif
#if Z4_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM(" I4 Z", stepperZ4.homing_threshold());
#endif
#if I_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_I_STR, stepperI.homing_threshold());
#endif
#if J_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_J_STR, stepperJ.homing_threshold());
#endif
#if K_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.homing_threshold());
#endif
#if U_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.homing_threshold());
#endif
#if V_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.homing_threshold());
#endif
#if W_SENSORLESS
say_M914(forReplay);
SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.homing_threshold());
#endif
}
#endif // USE_SENSORLESS

View file

@ -91,9 +91,9 @@ void GcodeSuite::M919() {
if (err) return;
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
#if ANY(X2_IS_TRINAMIC, Y2_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
const int8_t index = parser.byteval('I');
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
#elif ANY(X_IS_TRINAMIC, Y_IS_TRINAMIC, Z_IS_TRINAMIC)
constexpr int8_t index = -1;
#endif
@ -107,7 +107,7 @@ void GcodeSuite::M919() {
#define TMC_SET_CHOPPER_TIME(Q) stepper##Q.set_chopper_times(make_chopper_timing(CHOPPER_TIMING_##Q, toff, hend, hstrt))
#if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7)
#if ANY(E0_IS_TRINAMIC, E1_IS_TRINAMIC, E2_IS_TRINAMIC, E3_IS_TRINAMIC, E4_IS_TRINAMIC, E5_IS_TRINAMIC, E6_IS_TRINAMIC, E7_IS_TRINAMIC)
#define HAS_E_CHOPPER 1
int8_t eindex = -1;
#endif
@ -121,163 +121,66 @@ void GcodeSuite::M919() {
SERIAL_ECHOLNPGM(GCODE_ERR_MSG("Axis ", C(AXIS_CHAR(i)), " has no TMC drivers."));
break;
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2)
#if X_IS_TRINAMIC || X2_IS_TRINAMIC
case X_AXIS:
#if AXIS_IS_TMC(X)
if (index <= 0) TMC_SET_CHOPPER_TIME(X);
#endif
#if AXIS_IS_TMC(X2)
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(X2);
#endif
TERN_(X_IS_TRINAMIC, if (index <= 0) TMC_SET_CHOPPER_TIME(X));
TERN_(X2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(X2));
break;
#endif
#if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2)
#if Y_IS_TRINAMIC || Y2_IS_TRINAMIC
case Y_AXIS:
#if AXIS_IS_TMC(Y)
if (index <= 0) TMC_SET_CHOPPER_TIME(Y);
#endif
#if AXIS_IS_TMC(Y2)
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Y2);
#endif
TERN_(Y_IS_TRINAMIC, if (index <= 0) TMC_SET_CHOPPER_TIME(Y));
TERN_(Y2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Y2));
break;
#endif
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
#if ANY(Z_IS_TRINAMIC, Z2_IS_TRINAMIC, Z3_IS_TRINAMIC, Z4_IS_TRINAMIC)
case Z_AXIS:
#if AXIS_IS_TMC(Z)
if (index <= 0) TMC_SET_CHOPPER_TIME(Z);
#endif
#if AXIS_IS_TMC(Z2)
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Z2);
#endif
#if AXIS_IS_TMC(Z3)
if (index < 0 || index == 2) TMC_SET_CHOPPER_TIME(Z3);
#endif
#if AXIS_IS_TMC(Z4)
if (index < 0 || index == 3) TMC_SET_CHOPPER_TIME(Z4);
#endif
TERN_(Z_IS_TRINAMIC, if (index <= 0) TMC_SET_CHOPPER_TIME(Z));
TERN_(Z2_IS_TRINAMIC, if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Z2));
TERN_(Z3_IS_TRINAMIC, if (index < 0 || index == 2) TMC_SET_CHOPPER_TIME(Z3));
TERN_(Z4_IS_TRINAMIC, if (index < 0 || index == 3) TMC_SET_CHOPPER_TIME(Z4));
break;
#endif
#if AXIS_IS_TMC(I)
#if I_IS_TRINAMIC
case I_AXIS: TMC_SET_CHOPPER_TIME(I); break;
#endif
#if AXIS_IS_TMC(J)
#if J_IS_TRINAMIC
case J_AXIS: TMC_SET_CHOPPER_TIME(J); break;
#endif
#if AXIS_IS_TMC(K)
#if K_IS_TRINAMIC
case K_AXIS: TMC_SET_CHOPPER_TIME(K); break;
#endif
#if AXIS_IS_TMC(U)
#if U_IS_TRINAMIC
case U_AXIS: TMC_SET_CHOPPER_TIME(U); break;
#endif
#if AXIS_IS_TMC(V)
#if V_IS_TRINAMIC
case V_AXIS: TMC_SET_CHOPPER_TIME(V); break;
#endif
#if AXIS_IS_TMC(W)
#if W_IS_TRINAMIC
case W_AXIS: TMC_SET_CHOPPER_TIME(W); break;
#endif
#if HAS_E_CHOPPER
case E_AXIS: {
#if AXIS_IS_TMC(E0)
if (eindex <= 0) TMC_SET_CHOPPER_TIME(E0);
#endif
#if AXIS_IS_TMC(E1)
if (eindex < 0 || eindex == 1) TMC_SET_CHOPPER_TIME(E1);
#endif
#if AXIS_IS_TMC(E2)
if (eindex < 0 || eindex == 2) TMC_SET_CHOPPER_TIME(E2);
#endif
#if AXIS_IS_TMC(E3)
if (eindex < 0 || eindex == 3) TMC_SET_CHOPPER_TIME(E3);
#endif
#if AXIS_IS_TMC(E4)
if (eindex < 0 || eindex == 4) TMC_SET_CHOPPER_TIME(E4);
#endif
#if AXIS_IS_TMC(E5)
if (eindex < 0 || eindex == 5) TMC_SET_CHOPPER_TIME(E5);
#endif
#if AXIS_IS_TMC(E6)
if (eindex < 0 || eindex == 6) TMC_SET_CHOPPER_TIME(E6);
#endif
#if AXIS_IS_TMC(E7)
if (eindex < 0 || eindex == 7) TMC_SET_CHOPPER_TIME(E7);
#endif
TERN_(E0_IS_TRINAMIC, if (eindex <= 0) TMC_SET_CHOPPER_TIME(E0));
TERN_(E1_IS_TRINAMIC, if (eindex < 0 || eindex == 1) TMC_SET_CHOPPER_TIME(E1));
TERN_(E2_IS_TRINAMIC, if (eindex < 0 || eindex == 2) TMC_SET_CHOPPER_TIME(E2));
TERN_(E3_IS_TRINAMIC, if (eindex < 0 || eindex == 3) TMC_SET_CHOPPER_TIME(E3));
TERN_(E4_IS_TRINAMIC, if (eindex < 0 || eindex == 4) TMC_SET_CHOPPER_TIME(E4));
TERN_(E5_IS_TRINAMIC, if (eindex < 0 || eindex == 5) TMC_SET_CHOPPER_TIME(E5));
TERN_(E6_IS_TRINAMIC, if (eindex < 0 || eindex == 6) TMC_SET_CHOPPER_TIME(E6));
TERN_(E7_IS_TRINAMIC, if (eindex < 0 || eindex == 7) TMC_SET_CHOPPER_TIME(E7));
} break;
#endif
}
}
if (report) {
#define TMC_SAY_CHOPPER_TIME(Q) tmc_print_chopper_time(stepper##Q)
#if AXIS_IS_TMC(X)
TMC_SAY_CHOPPER_TIME(X);
#endif
#if AXIS_IS_TMC(X2)
TMC_SAY_CHOPPER_TIME(X2);
#endif
#if AXIS_IS_TMC(Y)
TMC_SAY_CHOPPER_TIME(Y);
#endif
#if AXIS_IS_TMC(Y2)
TMC_SAY_CHOPPER_TIME(Y2);
#endif
#if AXIS_IS_TMC(Z)
TMC_SAY_CHOPPER_TIME(Z);
#endif
#if AXIS_IS_TMC(Z2)
TMC_SAY_CHOPPER_TIME(Z2);
#endif
#if AXIS_IS_TMC(Z3)
TMC_SAY_CHOPPER_TIME(Z3);
#endif
#if AXIS_IS_TMC(Z4)
TMC_SAY_CHOPPER_TIME(Z4);
#endif
#if AXIS_IS_TMC(I)
TMC_SAY_CHOPPER_TIME(I);
#endif
#if AXIS_IS_TMC(J)
TMC_SAY_CHOPPER_TIME(J);
#endif
#if AXIS_IS_TMC(K)
TMC_SAY_CHOPPER_TIME(K);
#endif
#if AXIS_IS_TMC(U)
TMC_SAY_CHOPPER_TIME(U);
#endif
#if AXIS_IS_TMC(V)
TMC_SAY_CHOPPER_TIME(V);
#endif
#if AXIS_IS_TMC(W)
TMC_SAY_CHOPPER_TIME(W);
#endif
#if AXIS_IS_TMC(E0)
TMC_SAY_CHOPPER_TIME(E0);
#endif
#if AXIS_IS_TMC(E1)
TMC_SAY_CHOPPER_TIME(E1);
#endif
#if AXIS_IS_TMC(E2)
TMC_SAY_CHOPPER_TIME(E2);
#endif
#if AXIS_IS_TMC(E3)
TMC_SAY_CHOPPER_TIME(E3);
#endif
#if AXIS_IS_TMC(E4)
TMC_SAY_CHOPPER_TIME(E4);
#endif
#if AXIS_IS_TMC(E5)
TMC_SAY_CHOPPER_TIME(E5);
#endif
#if AXIS_IS_TMC(E6)
TMC_SAY_CHOPPER_TIME(E6);
#endif
#if AXIS_IS_TMC(E7)
TMC_SAY_CHOPPER_TIME(E7);
#endif
#define TMC_SAY_CHOPPER_TIME(Q) OPTCODE(Q##_IS_TRINAMIC, tmc_print_chopper_time(stepper##Q))
MAP(TMC_SAY_CHOPPER_TIME, ALL_AXIS_NAMES)
}
}

View file

@ -0,0 +1,144 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../../inc/MarlinConfigPre.h"
#if ENABLED(EDITABLE_HOMING_CURRENT)
#include "../../gcode.h"
#include "../../../feature/tmc_util.h"
#if AXIS_COLLISION('I')
#define I_PARAM 'S'
#define I_PARAM_STR "S"
#warning "Use 'M920 S' instead of 'M920 I' for the stepper number."
#else
#define I_PARAM 'I'
#define I_PARAM_STR "I"
#endif
/**
* M920: Set Homing Current for one or more axes
*
* Parameters:
* X[current] - Homing Current to use for X axis stepper(s)
* Y[current] - Homing Current to use for Y axis stepper(s)
* Z[current] - Homing Current to use for Z axis stepper(s)
* A[current] - Homing Current to use for A axis stepper(s)
* B[current] - Homing Current to use for B axis stepper(s)
* C[current] - Homing Current to use for C axis stepper(s)
* U[current] - Homing Current to use for U axis stepper(s)
* V[current] - Homing Current to use for V axis stepper(s)
* W[current] - Homing Current to use for W axis stepper(s)
*
* I<index> - For multi-stepper axes, the zero-based index of the stepper to modify in each axis.
* If omitted all steppers of each axis will be set to the given axis current.
*/
void GcodeSuite::M920() {
bool report = true;
const uint8_t index = parser.byteval(I_PARAM);
LOOP_NUM_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
const int16_t value = parser.value_int();
report = false;
switch (i) {
#if X_HAS_HOME_CURRENT
case X_AXIS:
if (index < 1) homing_current_mA.X = value;
TERN_(X2_HAS_HOME_CURRENT, if (!index || index == 1) homing_current_mA.X2 = value);
break;
#endif
#if Y_HAS_HOME_CURRENT
case Y_AXIS:
if (index < 1) homing_current_mA.Y = value;
TERN_(Y2_HAS_HOME_CURRENT, if (!index || index == 1) homing_current_mA.Y2 = value);
break;
#endif
#if Z_HAS_HOME_CURRENT
case Z_AXIS:
if (index < 1) homing_current_mA.Z = value;
TERN_(Z2_HAS_HOME_CURRENT, if (!index || index == 1) homing_current_mA.Z2 = value);
TERN_(Z3_HAS_HOME_CURRENT, if (!index || index == 2) homing_current_mA.Z3 = value);
TERN_(Z4_HAS_HOME_CURRENT, if (!index || index == 3) homing_current_mA.Z4 = value);
break;
#endif
OPTCODE(I_HAS_HOME_CURRENT, case I_AXIS: homing_current_mA.I = value; break)
OPTCODE(J_HAS_HOME_CURRENT, case J_AXIS: homing_current_mA.J = value; break)
OPTCODE(K_HAS_HOME_CURRENT, case K_AXIS: homing_current_mA.K = value; break)
OPTCODE(U_HAS_HOME_CURRENT, case U_AXIS: homing_current_mA.U = value; break)
OPTCODE(V_HAS_HOME_CURRENT, case V_AXIS: homing_current_mA.V = value; break)
OPTCODE(W_HAS_HOME_CURRENT, case W_AXIS: homing_current_mA.W = value; break)
}
}
if (report) M920_report();
}
void GcodeSuite::M920_report(const bool forReplay/*=true*/) {
TERN_(MARLIN_SMALL_BUILD, return);
report_heading(forReplay, F(STR_HOMING_CURRENT));
auto say_M920 = [](const bool forReplay, int16_t index=-1) {
report_echo_start(forReplay);
SERIAL_ECHOPGM(" M920");
if (index >= 0) SERIAL_ECHOPGM(" " I_PARAM_STR, index);
};
#if X_SENSORLESS || Y_SENSORLESS || Z_SENSORLESS
#if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS || Z3_SENSORLESS || Z4_SENSORLESS
say_M920(forReplay, 0);
#else
say_M920(forReplay);
#endif
TERN_(X_SENSORLESS, SERIAL_ECHOPGM_P(SP_X_STR, homing_current_mA.X));
TERN_(Y_SENSORLESS, SERIAL_ECHOPGM_P(SP_Y_STR, homing_current_mA.Y));
TERN_(Z_SENSORLESS, SERIAL_ECHOPGM_P(SP_Z_STR, homing_current_mA.Z));
#if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS || Z3_SENSORLESS || Z4_SENSORLESS
say_M920(forReplay);
#endif
TERN_(I_SENSORLESS, SERIAL_ECHOPGM_P(SP_I_STR, homing_current_mA.I));
TERN_(J_SENSORLESS, SERIAL_ECHOPGM_P(SP_J_STR, homing_current_mA.J));
TERN_(K_SENSORLESS, SERIAL_ECHOPGM_P(SP_K_STR, homing_current_mA.K));
TERN_(U_SENSORLESS, SERIAL_ECHOPGM_P(SP_U_STR, homing_current_mA.U));
TERN_(V_SENSORLESS, SERIAL_ECHOPGM_P(SP_V_STR, homing_current_mA.V));
TERN_(W_SENSORLESS, SERIAL_ECHOPGM_P(SP_W_STR, homing_current_mA.W));
SERIAL_EOL();
#endif
#if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS
say_M920(forReplay, 1);
TERN_(X2_SENSORLESS, SERIAL_ECHOPGM_P(SP_X_STR, homing_current_mA.X2));
TERN_(Y2_SENSORLESS, SERIAL_ECHOPGM_P(SP_Y_STR, homing_current_mA.Y2));
TERN_(Z2_SENSORLESS, SERIAL_ECHOPGM_P(SP_Z_STR, homing_current_mA.Z2));
SERIAL_EOL();
#endif
#if Z3_SENSORLESS
say_M920(forReplay, 2);
SERIAL_ECHOLNPGM(" Z", homing_current_mA.Z3);
#endif
#if Z4_SENSORLESS
say_M920(forReplay, 3);
SERIAL_ECHOLNPGM(" Z", homing_current_mA.Z4);
#endif
}
#endif // EDITABLE_HOMING_CURRENT

View file

@ -139,6 +139,7 @@ int8_t GcodeSuite::get_target_extruder_from_command() {
* Get the target E stepper from the 'T' parameter.
* If there is no 'T' parameter then dval will be substituted.
* Returns -1 if the resulting E stepper index is out of range.
* Use a default of -2 for silent failure.
*/
int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) {
const int8_t e = parser.intval('T', dval);
@ -242,11 +243,11 @@ void GcodeSuite::get_destination_from_command() {
}
/**
* Dwell waits immediately. It does not synchronize. Use M400 instead of G4
* Dwell waits immediately. It does not synchronize.
*/
void GcodeSuite::dwell(millis_t time) {
time += millis();
while (PENDING(millis(), time)) idle();
void GcodeSuite::dwell(const millis_t time) {
const millis_t start_ms = millis();
while (PENDING(millis(), start_ms, time)) idle();
}
/**
@ -947,6 +948,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 540: M540(); break; // M540: Set abort on endstop hit for SD printing
#endif
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
case 550: M550(); break; // M550: Set machine name
#endif
#if HAS_ETHERNET
case 552: M552(); break; // M552: Set IP address
case 553: M553(); break; // M553: Set gateway
@ -1051,12 +1056,15 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 912: M912(); break; // M912: Clear TMC2130 prewarn triggered flags
#endif
#if ENABLED(HYBRID_THRESHOLD)
case 913: M913(); break; // M913: Set HYBRID_THRESHOLD speed.
case 913: M913(); break; // M913: Set HYBRID_THRESHOLD speed
#endif
#if USE_SENSORLESS
case 914: M914(); break; // M914: Set StallGuard sensitivity.
case 914: M914(); break; // M914: Set StallGuard sensitivity
#endif
case 919: M919(); break; // M919: Set stepper Chopper Times
#if ENABLED(EDITABLE_HOMING_CURRENT)
case 920: M920(); break; // M920: Set Homing Current
#endif
#endif
#if HAS_MICROSTEPS

View file

@ -159,7 +159,7 @@
* M120 - Enable endstops detection.
* M121 - Disable endstops detection.
*
* M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M122 - Debug stepper (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660))
* M123 - Report fan tachometers. (Requires En_FAN_TACHO_PIN) Optionally set auto-report interval. (Requires AUTO_REPORT_FANS)
* M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE)
*
@ -261,10 +261,11 @@
* M512 - Set/Change/Remove Password (Requires PASSWORD_CHANGE_GCODE)
* M524 - Abort the current SD print job started with M24. (Requires SDSUPPORT)
* M540 - Enable/disable SD card abort on endstop hit: "M540 S<state>". (Requires SD_ABORT_ON_ENDSTOP_HIT)
* M550 - Set the machine name: "M550 P<name>". (Requires CONFIGURABLE_MACHINE_NAME)
* M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port)
* M553 - Get or set IP netmask. (Requires enabled Ethernet port)
* 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)
* M569 - Enable stealthChop on an axis. (Requires *_DRIVER_TYPE TMC(2130|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)
* M593 - Get or set input shaping parameters. (Requires INPUT_SHAPING_[XY])
@ -307,17 +308,19 @@
*
* M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND)
* M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER)
* M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE)
* M906 - Set or get motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M900 - Set or Report Linear Advance K-factor. (Requires LIN_ADVANCE)
* M906 - Set or Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660))
* M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots)
* M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN)
* M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC)
* M910 - Commit digipot/DAC value to external EEPROM via I2C. (Requires HAS_MOTOR_CURRENT_DAC)
* M911 - Report stepper driver overtemperature pre-warn condition. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M911 - Report stepper driver overtemperature pre-warn condition. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660))
* M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660))
* M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD)
* M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING)
* M919 - Get or Set motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc. If no parameters are given, report. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
* M919 - Set or Report motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc.
* If no parameters are given, report. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2660))
* M920 - Set Homing Current. (Requires distinct *_CURRENT_HOME settings)
* M936 - OTA update firmware. (Requires OTA_FIRMWARE_UPDATE)
* M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER)
* M3426 - Read MCP3426 ADC over I2C. (Requires HAS_MCP3426_ADC)
@ -430,14 +433,14 @@ public:
static millis_t previous_move_ms, max_inactive_time;
FORCE_INLINE static bool stepper_max_timed_out(const millis_t ms=millis()) {
return max_inactive_time && ELAPSED(ms, previous_move_ms + max_inactive_time);
return max_inactive_time && ELAPSED(ms, previous_move_ms, max_inactive_time);
}
FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; }
#if HAS_DISABLE_IDLE_AXES
static millis_t stepper_inactive_time;
FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) {
return ELAPSED(ms, previous_move_ms + stepper_inactive_time);
return ELAPSED(ms, previous_move_ms, stepper_inactive_time);
}
#else
static bool stepper_inactive_timeout(const millis_t) { return false; }
@ -502,7 +505,7 @@ public:
#define KEEPALIVE_STATE(N) NOOP
#endif
static void dwell(millis_t time);
static void dwell(const millis_t time);
private:
@ -1128,6 +1131,10 @@ private:
static void M540();
#endif
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
static void M550();
#endif
#if HAS_ETHERNET
static void M552();
static void M552_report();
@ -1253,6 +1260,10 @@ private:
static void M914_report(const bool forReplay=true);
#endif
static void M919();
#if ENABLED(EDITABLE_HOMING_CURRENT)
static void M920();
static void M920_report(const bool forReplay=true);
#endif
#endif
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM || HAS_MOTOR_CURRENT_I2C || HAS_MOTOR_CURRENT_DAC

View file

@ -33,7 +33,7 @@
*/
void GcodeSuite::M16() {
if (strcmp_P(parser.string_arg, PSTR(MACHINE_NAME)))
if (TERN(CONFIGURABLE_MACHINE_NAME, strcmp(parser.string_arg, machine_name), strcmp_P(parser.string_arg, PSTR(MACHINE_NAME))))
kill(GET_TEXT_F(MSG_KILL_EXPECTED_PRINTER));
}

View file

@ -37,6 +37,7 @@
* S<material>
* H<hotend temp>
* B<bed temp>
* C<chamber temp>
* F<fan speed>
*/
void GcodeSuite::M145() {
@ -53,6 +54,10 @@ void GcodeSuite::M145() {
if (parser.seenval('B'))
mat.bed_temp = constrain(parser.value_int(), BED_MINTEMP, BED_MAX_TARGET);
#endif
#if HAS_HEATED_CHAMBER
if (parser.seenval('C'))
mat.chamber_temp = constrain(parser.value_int(), CHAMBER_MINTEMP, CHAMBER_MAX_TARGET);
#endif
#if HAS_FAN
if (parser.seenval('F'))
mat.fan_speed = constrain(parser.value_int(), 0, 255);

View file

@ -426,7 +426,7 @@ void GCodeQueue::get_serial_commands() {
// send "wait" to indicate Marlin is still waiting.
#if NO_TIMEOUTS > 0
const millis_t ms = millis();
if (ring_buffer.empty() && !any_serial_data_available() && ELAPSED(ms, last_command_time + NO_TIMEOUTS)) {
if (ring_buffer.empty() && !any_serial_data_available() && ELAPSED(ms, last_command_time, NO_TIMEOUTS)) {
SERIAL_ECHOLNPGM(STR_WAIT);
last_command_time = ms;
}

View file

@ -39,9 +39,16 @@
*/
void GcodeSuite::M141() {
if (DEBUGGING(DRYRUN)) return;
// Accept 'I' if temperature presets are defined
#if HAS_PREHEAT
if (parser.seenval('I')) {
const uint8_t index = parser.value_byte();
thermalManager.setTargetChamber(ui.material_preset[_MIN(index, PREHEAT_COUNT - 1)].chamber_temp);
return;
}
#endif
if (parser.seenval('S')) {
thermalManager.setTargetChamber(parser.value_celsius());
#if ENABLED(PRINTJOB_TIMER_AUTOSTART)
/**
* Stop the timer at the end of print. Hotend, bed target, and chamber

View file

@ -189,6 +189,9 @@
#ifndef HOTEND_OVERSHOOT
#define HOTEND_OVERSHOOT 15
#endif
#ifndef MIN_POWER
#define MIN_POWER 0
#endif
#else
#undef MPCTEMP
#undef PIDTEMP

View file

@ -201,7 +201,7 @@
#define DOGLCD
#define IS_U8GLIB_ST7920 1
#define IS_ULTIPANEL 1
#define ENCODER_PULSES_PER_STEP 2
#define STD_ENCODER_PULSES_PER_STEP 2
#elif ENABLED(MKS_12864OLED)
@ -615,12 +615,20 @@
#define HAS_STATUS_MESSAGE 1
#endif
#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI
#define HAS_LCDPRINT 1
#if ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI)
#if ENABLED(STATUS_MESSAGE_SCROLLING)
#define MAX_MESSAGE_SIZE _MAX(LONG_FILENAME_LENGTH, MAX_LANG_CHARSIZE * (LCD_WIDTH))
#else
#define MAX_MESSAGE_SIZE (MAX_LANG_CHARSIZE * (LCD_WIDTH))
#endif
#elif HAS_STATUS_MESSAGE
#define MAX_MESSAGE_SIZE 63
#else
#define MAX_MESSAGE_SIZE 1
#endif
#if HAS_DISPLAY || HAS_LCDPRINT
#define HAS_UTF8_UTILS 1
#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI
#define HAS_LCDPRINT 1
#endif
#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS)
@ -649,7 +657,7 @@
#if !HAS_MARLINUI_HD44780
#undef LCD_INFO_SCREEN_STYLE
#endif
#if NONE(HAS_MARLINUI_U8GLIB, HAS_TFT_LVGL_UI, TFT_COLOR_UI, DGUS_LCD_UI_E3S1PRO)
#if NONE(HAS_MARLINUI_HD44780, HAS_MARLINUI_U8GLIB, HAS_TFT_LVGL_UI, TFT_COLOR_UI, DGUS_LCD_UI_E3S1PRO)
#undef LCD_LANGUAGE
#endif
#if DISABLED(MPC_AUTOTUNE)

View file

@ -135,7 +135,10 @@
#ifdef Z_PROBE_SERVO_NR
#define HAS_Z_SERVO_PROBE 1
#endif
#if ANY(HAS_Z_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
#ifdef MAG_MOUNTED_PROBE_SERVO_NR
#define HAS_MAG_MOUNTED_SERVO_PROBE 1
#endif
#if ANY(HAS_Z_SERVO_PROBE, HAS_MAG_MOUNTED_SERVO_PROBE, SWITCHING_EXTRUDER, SWITCHING_NOZZLE)
#define HAS_SERVO_ANGLES 1
#endif
#if !HAS_SERVO_ANGLES

View file

@ -53,6 +53,10 @@
#undef NUM_SERVOS
#define NUM_SERVOS INCREMENT(Z_PROBE_SERVO_NR)
#endif
#if HAS_MAG_MOUNTED_SERVO_PROBE && NUM_SERVOS <= MAG_MOUNTED_PROBE_SERVO_NR
#undef NUM_SERVOS
#define NUM_SERVOS INCREMENT(MAG_MOUNTED_PROBE_SERVO_NR)
#endif
#if ENABLED(CHAMBER_VENT) && NUM_SERVOS <= CHAMBER_VENT_SERVO_NR
#undef NUM_SERVOS
#define NUM_SERVOS INCREMENT(CHAMBER_VENT_SERVO_NR)
@ -1303,8 +1307,75 @@
#endif
#endif
#if AXIS_IS_TMC(X)
#define X_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Y)
#define Y_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Z)
#define Z_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(I)
#define I_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(J)
#define J_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(K)
#define K_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(U)
#define U_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(V)
#define V_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(W)
#define W_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(X2)
#define X2_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Y2)
#define Y2_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Z2)
#define Z2_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Z3)
#define Z3_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(Z4)
#define Z4_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E0)
#define E0_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E1)
#define E1_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E2)
#define E2_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E3)
#define E3_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E4)
#define E4_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E5)
#define E5_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E6)
#define E6_IS_TRINAMIC 1
#endif
#if AXIS_IS_TMC(E7)
#define E7_IS_TRINAMIC 1
#endif
// Test for edge stepping on any axis
#define AXIS_HAS_DEDGE(A) (ENABLED(EDGE_STEPPING) && AXIS_IS_TMC(A))
#define AXIS_HAS_DEDGE(A) ALL(EDGE_STEPPING, A##_IS_TRINAMIC)
#if ENABLED(DIRECT_STEPPING)
#ifndef STEPPER_PAGES

View file

@ -1052,7 +1052,7 @@
// Steppers
#if HAS_X_AXIS
#if PIN_EXISTS(X_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X))
#if PIN_EXISTS(X_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, X_IS_TRINAMIC)
#define HAS_X_ENABLE 1
#endif
#if PIN_EXISTS(X_DIR)
@ -1065,17 +1065,19 @@
#define HAS_X_MS_PINS 1
#endif
#if PIN_EXISTS(X2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(X2))
#define HAS_X2_ENABLE 1
#endif
#if PIN_EXISTS(X2_DIR)
#define HAS_X2_DIR 1
#endif
#if PIN_EXISTS(X2_STEP)
#define HAS_X2_STEP 1
#endif
#if PIN_EXISTS(X2_MS1)
#define HAS_X2_MS_PINS 1
#if HAS_X2_STEPPER
#if PIN_EXISTS(X2_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, X2_IS_TRINAMIC)
#define HAS_X2_ENABLE 1
#endif
#if PIN_EXISTS(X2_DIR)
#define HAS_X2_DIR 1
#endif
#if PIN_EXISTS(X2_STEP)
#define HAS_X2_STEP 1
#endif
#if PIN_EXISTS(X2_MS1)
#define HAS_X2_MS_PINS 1
#endif
#endif
#endif
@ -1084,7 +1086,7 @@
*/
#if HAS_Y_AXIS
#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
#if PIN_EXISTS(Y_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Y_IS_TRINAMIC)
#define HAS_Y_ENABLE 1
#endif
#if PIN_EXISTS(Y_DIR)
@ -1098,7 +1100,7 @@
#endif
#if HAS_Y2_STEPPER
#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
#if PIN_EXISTS(Y2_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Y2_IS_TRINAMIC)
#define HAS_Y2_ENABLE 1
#endif
#if PIN_EXISTS(Y2_DIR)
@ -1114,7 +1116,7 @@
#endif
#if HAS_Z_AXIS
#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
#if PIN_EXISTS(Z_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Z_IS_TRINAMIC)
#define HAS_Z_ENABLE 1
#endif
#if PIN_EXISTS(Z_DIR)
@ -1129,7 +1131,7 @@
#endif
#if NUM_Z_STEPPERS >= 2
#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
#if PIN_EXISTS(Z2_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Z2_IS_TRINAMIC)
#define HAS_Z2_ENABLE 1
#endif
#if PIN_EXISTS(Z2_DIR)
@ -1144,7 +1146,7 @@
#endif
#if NUM_Z_STEPPERS >= 3
#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
#if PIN_EXISTS(Z3_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Z3_IS_TRINAMIC)
#define HAS_Z3_ENABLE 1
#endif
#if PIN_EXISTS(Z3_DIR)
@ -1159,7 +1161,7 @@
#endif
#if NUM_Z_STEPPERS >= 4
#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
#if PIN_EXISTS(Z4_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, Z4_IS_TRINAMIC)
#define HAS_Z4_ENABLE 1
#endif
#if PIN_EXISTS(Z4_DIR)
@ -1174,7 +1176,7 @@
#endif
#if HAS_I_AXIS
#if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I))
#if PIN_EXISTS(I_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, I_IS_TRINAMIC)
#define HAS_I_ENABLE 1
#endif
#if PIN_EXISTS(I_DIR)
@ -1189,7 +1191,7 @@
#endif
#if HAS_J_AXIS
#if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J))
#if PIN_EXISTS(J_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, J_IS_TRINAMIC)
#define HAS_J_ENABLE 1
#endif
#if PIN_EXISTS(J_DIR)
@ -1204,7 +1206,7 @@
#endif
#if HAS_K_AXIS
#if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K))
#if PIN_EXISTS(K_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, K_IS_TRINAMIC)
#define HAS_K_ENABLE 1
#endif
#if PIN_EXISTS(K_DIR)
@ -1219,7 +1221,7 @@
#endif
#if HAS_U_AXIS
#if PIN_EXISTS(U_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(U))
#if PIN_EXISTS(U_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, U_IS_TRINAMIC)
#define HAS_U_ENABLE 1
#endif
#if PIN_EXISTS(U_DIR)
@ -1234,7 +1236,7 @@
#endif
#if HAS_V_AXIS
#if PIN_EXISTS(V_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(V))
#if PIN_EXISTS(V_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, V_IS_TRINAMIC)
#define HAS_V_ENABLE 1
#endif
#if PIN_EXISTS(V_DIR)
@ -1249,7 +1251,7 @@
#endif
#if HAS_W_AXIS
#if PIN_EXISTS(W_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(W))
#if PIN_EXISTS(W_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, W_IS_TRINAMIC)
#define HAS_W_ENABLE 1
#endif
#if PIN_EXISTS(W_DIR)
@ -1266,7 +1268,7 @@
// Extruder steppers and solenoids
#if HAS_EXTRUDERS
#if PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))
#if PIN_EXISTS(E0_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E0_IS_TRINAMIC)
#define HAS_E0_ENABLE 1
#endif
#if PIN_EXISTS(E0_DIR)
@ -1280,7 +1282,7 @@
#endif
#if E_STEPPERS > 1 || ENABLED(E_DUAL_STEPPER_DRIVERS)
#if PIN_EXISTS(E1_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E1))
#if PIN_EXISTS(E1_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E1_IS_TRINAMIC)
#define HAS_E1_ENABLE 1
#endif
#if PIN_EXISTS(E1_DIR)
@ -1295,7 +1297,7 @@
#endif
#if E_STEPPERS > 2
#if PIN_EXISTS(E2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E2))
#if PIN_EXISTS(E2_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E2_IS_TRINAMIC)
#define HAS_E2_ENABLE 1
#endif
#if PIN_EXISTS(E2_DIR)
@ -1310,7 +1312,7 @@
#endif
#if E_STEPPERS > 3
#if PIN_EXISTS(E3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E3))
#if PIN_EXISTS(E3_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E3_IS_TRINAMIC)
#define HAS_E3_ENABLE 1
#endif
#if PIN_EXISTS(E3_DIR)
@ -1325,7 +1327,7 @@
#endif
#if E_STEPPERS > 4
#if PIN_EXISTS(E4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E4))
#if PIN_EXISTS(E4_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E4_IS_TRINAMIC)
#define HAS_E4_ENABLE 1
#endif
#if PIN_EXISTS(E4_DIR)
@ -1340,7 +1342,7 @@
#endif
#if E_STEPPERS > 5
#if PIN_EXISTS(E5_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E5))
#if PIN_EXISTS(E5_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E5_IS_TRINAMIC)
#define HAS_E5_ENABLE 1
#endif
#if PIN_EXISTS(E5_DIR)
@ -1355,7 +1357,7 @@
#endif
#if E_STEPPERS > 6
#if PIN_EXISTS(E6_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E6))
#if PIN_EXISTS(E6_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E6_IS_TRINAMIC)
#define HAS_E6_ENABLE 1
#endif
#if PIN_EXISTS(E6_DIR)
@ -1370,7 +1372,7 @@
#endif
#if E_STEPPERS > 7
#if PIN_EXISTS(E7_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E7))
#if PIN_EXISTS(E7_ENABLE) || ALL(SOFTWARE_DRIVER_ENABLE, E7_IS_TRINAMIC)
#define HAS_E7_ENABLE 1
#endif
#if PIN_EXISTS(E7_DIR)
@ -1441,7 +1443,7 @@
#undef Z4_STALL_SENSITIVITY
#endif
#if AXIS_IS_TMC(X)
#if X_IS_TRINAMIC
#if defined(X_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X)
#define X_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(X)
@ -1461,7 +1463,7 @@
#define X_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(X2)
#if X2_IS_TRINAMIC
#if defined(X2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2)
#define X2_SENSORLESS 1
#endif
@ -1479,7 +1481,7 @@
#endif
#endif
#if AXIS_IS_TMC(Y)
#if Y_IS_TRINAMIC
#if defined(Y_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y)
#define Y_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(Y)
@ -1499,7 +1501,7 @@
#define Y_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(Y2)
#if Y2_IS_TRINAMIC
#if defined(Y2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2)
#define Y2_SENSORLESS 1
#endif
@ -1517,7 +1519,7 @@
#endif
#endif
#if AXIS_IS_TMC(Z)
#if Z_IS_TRINAMIC
#if defined(Z_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z)
#define Z_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(Z)
@ -1537,7 +1539,7 @@
#define Z_SLAVE_ADDRESS 0
#endif
#endif
#if NUM_Z_STEPPERS >= 2 && AXIS_IS_TMC(Z2)
#if NUM_Z_STEPPERS >= 2 && Z2_IS_TRINAMIC
#if defined(Z2_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2)
#define Z2_SENSORLESS 1
#endif
@ -1554,7 +1556,7 @@
#define Z2_SLAVE_ADDRESS 0
#endif
#endif
#if NUM_Z_STEPPERS >= 3 && AXIS_IS_TMC(Z3)
#if NUM_Z_STEPPERS >= 3 && Z3_IS_TRINAMIC
#if defined(Z3_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3)
#define Z3_SENSORLESS 1
#endif
@ -1571,7 +1573,7 @@
#define Z3_SLAVE_ADDRESS 0
#endif
#endif
#if NUM_Z_STEPPERS >= 4 && AXIS_IS_TMC(Z4)
#if NUM_Z_STEPPERS >= 4 && Z4_IS_TRINAMIC
#if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4)
#define Z4_SENSORLESS 1
#endif
@ -1589,7 +1591,7 @@
#endif
#endif
#if AXIS_IS_TMC(I)
#if I_IS_TRINAMIC
#if defined(I_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(I)
#define I_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(I)
@ -1610,7 +1612,7 @@
#endif
#endif
#if AXIS_IS_TMC(J)
#if J_IS_TRINAMIC
#if defined(J_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(J)
#define J_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(J)
@ -1631,7 +1633,7 @@
#endif
#endif
#if AXIS_IS_TMC(K)
#if K_IS_TRINAMIC
#if defined(K_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(K)
#define K_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(K)
@ -1652,7 +1654,7 @@
#endif
#endif
#if AXIS_IS_TMC(U)
#if U_IS_TRINAMIC
#if defined(U_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(U)
#define U_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(U)
@ -1673,7 +1675,7 @@
#endif
#endif
#if AXIS_IS_TMC(V)
#if V_IS_TRINAMIC
#if defined(V_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(V)
#define V_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(V)
@ -1694,7 +1696,7 @@
#endif
#endif
#if AXIS_IS_TMC(W)
#if W_IS_TRINAMIC
#if defined(W_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(W)
#define W_SENSORLESS 1
#if ENABLED(SPI_ENDSTOPS) && AXIS_HAS_SPI(W)
@ -1715,7 +1717,7 @@
#endif
#endif
#if AXIS_IS_TMC(E0)
#if E0_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E0)
#define E0_HAS_STEALTHCHOP 1
#endif
@ -1729,7 +1731,7 @@
#define E0_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E1)
#if E1_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E1)
#define E1_HAS_STEALTHCHOP 1
#endif
@ -1743,7 +1745,7 @@
#define E1_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E2)
#if E2_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E2)
#define E2_HAS_STEALTHCHOP 1
#endif
@ -1757,7 +1759,7 @@
#define E2_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E3)
#if E3_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E3)
#define E3_HAS_STEALTHCHOP 1
#endif
@ -1771,7 +1773,7 @@
#define E3_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E4)
#if E4_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E4)
#define E4_HAS_STEALTHCHOP 1
#endif
@ -1785,7 +1787,7 @@
#define E4_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E5)
#if E5_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E5)
#define E5_HAS_STEALTHCHOP 1
#endif
@ -1799,7 +1801,7 @@
#define E5_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E6)
#if E6_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E6)
#define E6_HAS_STEALTHCHOP 1
#endif
@ -1813,7 +1815,7 @@
#define E6_SLAVE_ADDRESS 0
#endif
#endif
#if AXIS_IS_TMC(E7)
#if E7_IS_TRINAMIC
#if AXIS_HAS_STEALTHCHOP(E7)
#define E7_HAS_STEALTHCHOP 1
#endif
@ -2991,7 +2993,10 @@
#if ANY_PIN(MOTOR_CURRENT_PWM_E, MOTOR_CURRENT_PWM_E0, MOTOR_CURRENT_PWM_E1)
#define HAS_MOTOR_CURRENT_PWM_E 1
#endif
#if HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
#define HAS_MOTOR_CURRENT_PWM_Z 1
#endif
#if HAS_MOTOR_CURRENT_PWM_Z || HAS_MOTOR_CURRENT_PWM_E || ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
#define HAS_MOTOR_CURRENT_PWM 1
#endif

View file

@ -38,10 +38,53 @@
#endif
// If an axis's Homing Current differs from standard current...
#define HAS_CURRENT_HOME(N) (N##_CURRENT_HOME > 0 && N##_CURRENT_HOME != N##_CURRENT)
#define HAS_HOME_CURRENT(N) TERN0(EDITABLE_HOMING_CURRENT, N##_IS_TRINAMIC && N##_HOME_DIR != 0) || (N##_CURRENT_HOME > 0 && N##_CURRENT_HOME != N##_CURRENT)
#if HAS_HOME_CURRENT(X)
#define X_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Y)
#define Y_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Z)
#define Z_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(I)
#define I_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(J)
#define J_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(K)
#define K_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(U)
#define U_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(V)
#define V_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(W)
#define W_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(X2)
#define X2_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Y2)
#define Y2_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Z2)
#define Z2_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Z3)
#define Z3_HAS_HOME_CURRENT 1
#endif
#if HAS_HOME_CURRENT(Z4)
#define Z4_HAS_HOME_CURRENT 1
#endif
#undef HAS_HOME_CURRENT
// Does any axis have homing current?
#define _OR_HAS_CURR_HOME(N) HAS_CURRENT_HOME(N) ||
#define _OR_HAS_CURR_HOME(N) N##_HAS_HOME_CURRENT ||
#if MAIN_AXIS_MAP(_OR_HAS_CURR_HOME) MAP(_OR_HAS_CURR_HOME, X2, Y2, Z2, Z3, Z4) 0
#define HAS_HOMING_CURRENT 1
#endif

View file

@ -241,10 +241,10 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L
#error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices."
#endif
// Serial DMA is only available for some STM32 MCUs and HC32
// Serial DMA is only available for some STM32 MCUs, HC32 and GD32
#if ENABLED(SERIAL_DMA)
#ifdef ARDUINO_ARCH_HC32
// checks for HC32 are located in HAL/HC32/inc/SanityCheck.h
#if ANY(ARDUINO_ARCH_HC32, ARDUINO_ARCH_MFL)
// See HAL/.../inc/SanityCheck.h
#elif DISABLED(HAL_STM32) || NONE(STM32F0xx, STM32F1xx, STM32F2xx, STM32F4xx, STM32F7xx, STM32H7xx)
#error "SERIAL_DMA is only available for some STM32 MCUs and requires HAL/STM32."
#elif !defined(HAL_UART_MODULE_ENABLED) || defined(HAL_UART_MODULE_ONLY)
@ -982,7 +982,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
/**
* Servo deactivation depends on servo endstops, switching nozzle, or switching extruder
*/
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && NONE(HAS_Z_SERVO_PROBE, POLARGRAPH) && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR) && !defined(SWITCHING_TOOLHEAD_SERVO_NR)
#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && NONE(HAS_Z_SERVO_PROBE, POLARGRAPH) && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR) && !defined(SWITCHING_TOOLHEAD_SERVO_NR) && !defined(MAG_MOUNTED_PROBE_SERVO_NR)
#error "Z_PROBE_SERVO_NR, switching nozzle, switching toolhead, switching extruder, or POLARGRAPH is required for DEACTIVATE_SERVOS_AFTER_MOVE."
#endif
@ -1805,8 +1805,8 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#undef _BAD_HOME_CURRENT
#if ENABLED(PROBING_USE_CURRENT_HOME)
#if (defined(Z_CURRENT_HOME) && !HAS_CURRENT_HOME(Z)) || (defined(Z2_CURRENT_HOME) && !HAS_CURRENT_HOME(Z2)) \
|| (defined(Z3_CURRENT_HOME) && !HAS_CURRENT_HOME(Z3)) || (defined(Z4_CURRENT_HOME) && !HAS_CURRENT_HOME(Z4))
#if (defined(Z_CURRENT_HOME) && !Z_HAS_HOME_CURRENT) || (defined(Z2_CURRENT_HOME) && !Z2_HAS_HOME_CURRENT) \
|| (defined(Z3_CURRENT_HOME) && !Z3_HAS_HOME_CURRENT) || (defined(Z4_CURRENT_HOME) && !Z4_HAS_HOME_CURRENT)
#error "PROBING_USE_CURRENT_HOME requires a Z_CURRENT_HOME value that differs from Z_CURRENT."
#endif
#endif
@ -1888,9 +1888,9 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#endif
/**
* ULTIPANEL encoder
* ULTIPANEL expects an encoder
*/
#if IS_ULTIPANEL && NONE(IS_NEWPANEL, SR_LCD_2W_NL) && !PIN_EXISTS(SHIFT_CLK)
#if IS_ULTIPANEL && NONE(HAS_ROTARY_ENCODER, SR_LCD_2W_NL, SR_LCD_3W_NL, TOUCH_SCREEN) && !ANY_PIN(SHIFT_CLK, ADC_KEYPAD)
#error "ULTIPANEL controllers require some kind of encoder."
#endif
@ -2452,28 +2452,28 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#endif
#endif
#if E_STEPPERS > 0 && !(PINS_EXIST(E0_STEP, E0_DIR) && HAS_E0_ENABLE)
#if E_STEPPERS > 0 && !ALL(HAS_E0_DIR, HAS_E0_STEP, HAS_E0_ENABLE)
#error "E0_STEP_PIN, E0_DIR_PIN, or E0_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 1 && !(PINS_EXIST(E1_STEP, E1_DIR) && HAS_E1_ENABLE)
#if E_STEPPERS > 1 && !ALL(HAS_E1_DIR, HAS_E1_STEP, HAS_E1_ENABLE)
#error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 2 && !(PINS_EXIST(E2_STEP, E2_DIR) && HAS_E2_ENABLE)
#if E_STEPPERS > 2 && !ALL(HAS_E2_DIR, HAS_E2_STEP, HAS_E2_ENABLE)
#error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 3 && !(PINS_EXIST(E3_STEP, E3_DIR) && HAS_E3_ENABLE)
#if E_STEPPERS > 3 && !ALL(HAS_E3_DIR, HAS_E3_STEP, HAS_E3_ENABLE)
#error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 4 && !(PINS_EXIST(E4_STEP, E4_DIR) && HAS_E4_ENABLE)
#if E_STEPPERS > 4 && !ALL(HAS_E4_DIR, HAS_E4_STEP, HAS_E4_ENABLE)
#error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 5 && !(PINS_EXIST(E5_STEP, E5_DIR) && HAS_E5_ENABLE)
#if E_STEPPERS > 5 && !ALL(HAS_E5_DIR, HAS_E5_STEP, HAS_E5_ENABLE)
#error "E5_STEP_PIN, E5_DIR_PIN, or E5_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 6 && !(PINS_EXIST(E6_STEP, E6_DIR) && HAS_E6_ENABLE)
#if E_STEPPERS > 6 && !ALL(HAS_E6_DIR, HAS_E6_STEP, HAS_E6_ENABLE)
#error "E6_STEP_PIN, E6_DIR_PIN, or E6_ENABLE_PIN not defined for this board."
#endif
#if E_STEPPERS > 7 && !(PINS_EXIST(E7_STEP, E7_DIR) && HAS_E7_ENABLE)
#if E_STEPPERS > 7 && !ALL(HAS_E7_DIR, HAS_E7_STEP, HAS_E7_ENABLE)
#error "E7_STEP_PIN, E7_DIR_PIN, or E7_ENABLE_PIN not defined for this board."
#endif
@ -3230,7 +3230,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#undef INVALID_TMC_ADDRESS
#define _TMC_MICROSTEP_IS_VALID(MS) (MS == 0 || MS == 2 || MS == 4 || MS == 8 || MS == 16 || MS == 32 || MS == 64 || MS == 128 || MS == 256)
#define TMC_MICROSTEP_IS_VALID(M) (!AXIS_IS_TMC(M) || _TMC_MICROSTEP_IS_VALID(M##_MICROSTEPS))
#define TMC_MICROSTEP_IS_VALID(M) (!M##_IS_TRINAMIC || _TMC_MICROSTEP_IS_VALID(M##_MICROSTEPS))
#define INVALID_TMC_MS(ST) static_assert(0, "Invalid " STRINGIFY(ST) "_MICROSTEPS. Valid values are 0, 2, 4, 8, 16, 32, 64, 128, and 256.")
#if !TMC_MICROSTEP_IS_VALID(X)
@ -4041,11 +4041,11 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive."
#elif _PIN_CONFLICT(CONTROLLERFAN)
#error "SPINDLE_LASER_PWM_PIN conflicts with CONTROLLERFAN_PIN."
#elif _PIN_CONFLICT(MOTOR_CURRENT_PWM_XY)
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_XY."
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_XY_PIN."
#elif _PIN_CONFLICT(MOTOR_CURRENT_PWM_Z)
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_Z."
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_Z_PIN."
#elif _PIN_CONFLICT(MOTOR_CURRENT_PWM_E)
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_E."
#error "SPINDLE_LASER_PWM_PIN conflicts with MOTOR_CURRENT_PWM_E_PIN."
#endif
#endif
#undef _PIN_CONFLICT
@ -4507,6 +4507,10 @@ static_assert(WITHIN(MULTISTEPPING_LIMIT, 1, 128) && IS_POWER_OF_2(MULTISTEPPING
#error "Only enable ULTIPANEL_FEEDMULTIPLY or ULTIPANEL_FLOWPERCENT, but not both."
#endif
#if ENABLED(CONFIGURABLE_MACHINE_NAME) && DISABLED(GCODE_QUOTED_STRINGS)
#error "CONFIGURABLE_MACHINE_NAME requires GCODE_QUOTED_STRINGS."
#endif
// Misc. Cleanup
#undef _TEST_PWM
#undef _NUM_AXES_STR

View file

@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
#define STRING_DISTRIBUTION_DATE "2025-03-10"
#define STRING_DISTRIBUTION_DATE "2025-04-01"
#endif
/**

View file

@ -696,9 +696,16 @@
#warning "Don't forget to update your TFT settings in Configuration.h."
#endif
#if ENABLED(EMIT_CREALITY_422_WARNING) && DISABLED(NO_CREALITY_422_DRIVER_WARNING)
// Driver labels: A=TMC2208, B=TMC2209, C=HR4988, E=A4988, H=TMC2225, H8=HR4988
#warning "Creality 4.2.2 boards come with a variety of stepper drivers. Check the board label (typically on SD Card module) and set the correct *_DRIVER_TYPE! (A/H: TMC2208_STANDALONE B: TMC2209_STANDALONE C/E/H8: A4988). (Define NO_CREALITY_422_DRIVER_WARNING to suppress this warning.)"
#if ENABLED(EMIT_CREALITY_422_WARNING)
#if DISABLED(NO_CREALITY_422_MCU_WARNING)
#warning "Double-check your 4.2.2 board for STM32 / GD32. Use BOARD_CREALITY_V422 or BOARD_CREALITY_V422_GD32_MFL as appropriate for your MCU."
#warning "GD32 Serial Ports are numbered starting from 0. STM32 Serial Ports are numbered starting from 1."
#warning "(Define NO_CREALITY_422_MCU_WARNING to suppress these warnings.)"
#endif
#if DISABLED(NO_CREALITY_422_DRIVER_WARNING)
// Driver labels: A=TMC2208, B=TMC2209, C=HR4988, E=A4988, H=TMC2225, H8=HR4988
#warning "Creality 4.2.2 boards come with a variety of stepper drivers. Check the board label (typically on SD Card module) and set the correct *_DRIVER_TYPE! (A/H: TMC2208_STANDALONE B: TMC2209_STANDALONE C/E/H8: A4988). (Define NO_CREALITY_422_DRIVER_WARNING to suppress this warning.)"
#endif
#endif
#if ENABLED(PRINTCOUNTER_SYNC)
@ -742,24 +749,24 @@
#endif
#if USE_SENSORLESS && DISABLED(NO_HOMING_CURRENT_WARNING)
#if ENABLED(X_SENSORLESS) && defined(X_CURRENT_HOME) && !HAS_CURRENT_HOME(X)
#warning "It's recommended to set X_CURRENT_HOME lower than X_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(X2_SENSORLESS) && defined(X2_CURRENT_HOME) && !HAS_CURRENT_HOME(X2)
#warning "It's recommended to set X2_CURRENT_HOME lower than X2_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#if ENABLED(X_SENSORLESS) && defined(X_CURRENT_HOME) && !X_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set X_CURRENT_HOME less than X_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(X2_SENSORLESS) && defined(X2_CURRENT_HOME) && !X2_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set X2_CURRENT_HOME less than X2_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#endif
#if ENABLED(Y_SENSORLESS) && defined(Y_CURRENT_HOME) && !HAS_CURRENT_HOME(Y)
#warning "It's recommended to set Y_CURRENT_HOME lower than Y_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Y2_SENSORLESS) && defined(Y2_CURRENT_HOME) && !HAS_CURRENT_HOME(Y2)
#warning "It's recommended to set Y2_CURRENT_HOME lower than Y2_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#if ENABLED(Y_SENSORLESS) && defined(Y_CURRENT_HOME) && !Y_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Y_CURRENT_HOME less than Y_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Y2_SENSORLESS) && defined(Y2_CURRENT_HOME) && !Y2_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Y2_CURRENT_HOME less than Y2_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#endif
#if ENABLED(Z_SENSORLESS) && defined(Z_CURRENT_HOME) && !HAS_CURRENT_HOME(Z)
#warning "It's recommended to set Z_CURRENT_HOME lower than Z_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z2_SENSORLESS) && defined(Z2_CURRENT_HOME) && !HAS_CURRENT_HOME(Z2)
#warning "It's recommended to set Z2_CURRENT_HOME lower than Z2_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z3_SENSORLESS) && defined(Z3_CURRENT_HOME) && !HAS_CURRENT_HOME(Z3)
#warning "It's recommended to set Z3_CURRENT_HOME lower than Z3_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z4_SENSORLESS) && defined(Z4_CURRENT_HOME) && !HAS_CURRENT_HOME(Z4)
#warning "It's recommended to set Z4_CURRENT_HOME lower than Z4_CURRENT with SENSORLESS_HOMING. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#if ENABLED(Z_SENSORLESS) && defined(Z_CURRENT_HOME) && !Z_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Z_CURRENT_HOME less than Z_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z2_SENSORLESS) && defined(Z2_CURRENT_HOME) && !Z2_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Z2_CURRENT_HOME less than Z2_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z3_SENSORLESS) && defined(Z3_CURRENT_HOME) && !Z3_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Z3_CURRENT_HOME less than Z3_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#elif ENABLED(Z4_SENSORLESS) && defined(Z4_CURRENT_HOME) && !Z4_HAS_HOME_CURRENT
#warning "With SENSORLESS_HOMING it is recommended to set Z4_CURRENT_HOME less than Z4_CURRENT. (Define NO_HOMING_CURRENT_WARNING to suppress this warning.)"
#endif
#endif
@ -898,6 +905,13 @@
#warning "The (-1) AD595 Thermocouple Amplifier requires 5V input supply! Use AD8495 for 3.3V ADC."
#endif
/**
* MKS_TINYBEE Analog Reference
*/
#if ENABLED(EMIT_ADC_REFERENCE_VOLTAGE_WARNING)
#warning "Check your ADC_REFERENCE_VOLTAGE on MKS TinyBee! Measure the Analog Reference voltage on the board. See pins_MKS_TINYBEE.h for details."
#endif
/**
* No PWM on the Piezo Beeper?
*/
@ -925,3 +939,10 @@
#if ALL(PELTIER_BED, PIDTEMPBED)
#warning "PELTIER_BED with PIDTEMPBED requires extra circuitry. Use with caution."
#endif
/**
* Board recommended LCD_SERIAL_PORT
*/
#if LCD_IS_SERIAL_HOST && defined(BOARD_LCD_SERIAL_PORT) && LCD_SERIAL_PORT != BOARD_LCD_SERIAL_PORT && DISABLED(NO_LCD_SERIAL_PORT_WARNING)
#warning "LCD_SERIAL_PORT overrides the default (BOARD_LCD_SERIAL_PORT)."
#endif

View file

@ -755,7 +755,7 @@ void MarlinUI::draw_status_message(const bool blink) {
// Draw the progress bar if the message has shown long enough
// or if there is no message set.
if (ELAPSED(millis(), progress_bar_ms + PROGRESS_BAR_MSG_TIME) || !has_status()) {
if (ELAPSED(millis(), progress_bar_ms, PROGRESS_BAR_MSG_TIME) || !has_status()) {
const uint8_t progress = get_progress_percent();
if (progress > 2) return draw_progress_bar(progress);
}

View file

@ -31,8 +31,8 @@ void MarlinGame::frame_start() {
void MarlinGame::frame_end() {}
void MarlinGame::set_color(const color color) {
switch (color) {
void MarlinGame::set_color(const color clr) {
switch (clr) {
default:
case color::WHITE: u8g.setColorIndex(1); break;
case color::BLACK: u8g.setColorIndex(0); break;

View file

@ -1,3 +1,25 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2018 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/>.
*
*/
/**
* @file lcdprint_u8g.cpp
* @brief LCD print api for u8glib

View file

@ -38,19 +38,19 @@
#if HAS_MEDIA
#ifdef __SAMD21__
#define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL
#define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL // 2 stripes, HW SPI (Shared with SD card. Non-standard LCD adapter on AVR.)
#else
// Hardware SPI on DUE
#define U8G_CLASS U8GLIB_ST7920_128X64_4X
#define U8G_CLASS U8GLIB_ST7920_128X64_4X // 2 stripes, SW SPI (Original u8glib device)
#endif
#define U8G_PARAM LCD_PINS_RS
#elif (LCD_PINS_D4 == SD_SCK_PIN) && (LCD_PINS_EN == SD_MOSI_PIN)
// Hardware SPI shared with SD Card
#define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL
#define U8G_CLASS U8GLIB_ST7920_128X64_4X_HAL // 2 stripes, HW SPI (Shared with SD card. Non-standard LCD adapter on AVR.)
#define U8G_PARAM LCD_PINS_RS
#else
// Software SPI
#define U8G_CLASS U8GLIB_ST7920_128X64_4X
#define U8G_CLASS U8GLIB_ST7920_128X64_4X // 2 stripes, SW SPI (Original u8glib device)
#define U8G_PARAM LCD_PINS_D4, LCD_PINS_EN, LCD_PINS_RS
#endif
@ -201,7 +201,7 @@
// Generic support for SSD1309 OLED I2C LCDs
#define U8G_CLASS U8GLIB_SSD1309_128X64
#define U8G_CLASS TERN(LCD_DOUBLE_BUFFER, U8GLIB_SSD1309_128X64_F, U8GLIB_SSD1309_128X64)
#define U8G_PARAM (U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST) // I2C
#elif ENABLED(U8GLIB_SSD1306)

View file

@ -75,58 +75,58 @@
#define HEIGHT 64
#define PAGE_HEIGHT 8
#define CMD_COL_ADR(N) (0x10 | ((N) >> 4)), ((N) & 0xF)
#define CMD_PAGE_ADR(N) (0x20), (N)
#define CMD_COLUMN_RANGE(N,O) (0x21), (N), (O)
#define CMD_PAGE_RANGE(N,O) (0x22), (N), (O)
#define CMD_SCROLL(N) ((N) ? 0x2F : 0x2E)
#define CMD_START_LINE(N) (0x40 | (N))
#define CMD_CONTRAST(N) (0x81), (N)
#define CMD_CHARGE_PUMP(N) (0x8D), ((N) ? 0x14 : 0x10)
#define CMD_ADC_REVERSE(N) ((N) ? 0xA1 : 0xA0)
#define CMD_ALL_PIX(N) ((N) ? 0xA5 : 0xA4)
#define CMD_INVERTED(N) ((N) ? 0xA7 : 0xA6)
#define CMD_MUX_RATIO(N) (0xA8), (N)
#define CMD_ON(N) ((N) ? 0xAF : 0xAE)
#define CMD_OUT_MODE(N) ((N) ? 0xC8 : 0xC0)
#define CMD_DISP_OFFS(N) (0xD3), (N)
#define CMD_OSC_FREQ(R,F) (0xD5), ((F) << 4 | (R))
#define CMD_CHARGE_PER(P,D) (0xD9), ((D) << 4 | (P))
#define CMD_COM_CONFIG(N) (0xDA), ((N) ? 0x12 : 0x02)
#define CMD_VCOM_DESEL(N) (0xDB), (N)
#define CMD_NOOP() (0xE3)
uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_seq);
// SH1106 (132x64) is compatible with SSD1306 (128x64) by adding a small margin to the larger display
#define SH1106_PAGE_ADR(N) (0x20), (N)
#define SH1106_COL_ADR(N) (0x10 | ((N) >> 4)), ((N) & 0xFF)
#define SH1106_COLUMN_RANGE(N,O) (0x21), (N), (O)
#define SH1106_PAGE_RANGE(N,O) (0x22), (N), (O)
#define SH1106_SCROLL(N) ((N) ? 0x2F : 0x2E)
#define SH1106_START_LINE(N) (0x40 | (N))
#define SH1106_CONTRAST(N) (0x81), (N)
#define SH1106_CHARGE_PUMP(N) (0x8D), ((N) ? 0x14 : 0x10)
#define SH1106_ADC_REVERSE(N) ((N) ? 0xA1 : 0xA0)
#define SH1106_ALL_PIX(N) ((N) ? 0xA5 : 0xA4)
#define SH1106_INVERTED(N) ((N) ? 0xA7 : 0xA6)
#define SH1106_MUX_RATIO(N) (0xA8), (N)
#define SH1106_ON(N) ((N) ? 0xAF : 0xAE)
#define SH1106_OUT_MODE(N) ((N) ? 0xC8 : 0xC0)
#define SH1106_DISP_OFFS(N) (0xD3), (N)
#define SH1106_OSC_FREQ(R,F) (0xD5), ((F) << 4 | (R))
#define SH1106_CHARGE_PER(P,D) (0xD9), ((D) << 4 | (P))
#define SH1106_COM_CONFIG(N) (0xDA), ((N) ? 0x12 : 0x02)
#define SH1106_VCOM_DESEL(N) (0xDB), (N)
#define SH1106_NOOP() (0xE3)
// SH1106 is compatible with SSD1306, but is 132x64. Display 128x64 centered within the 132x64.
static const uint8_t u8g_dev_sh1106_128x64_data_start_2_wire[] PROGMEM = {
SH1106_COL_ADR(2), // Column 2 to center 128 pixels in 132 pixels
U8G_ESC_END // End of sequence
CMD_COL_ADR(2), // Column 2 to center 128 pixels in 132 pixels
U8G_ESC_END // End of sequence
};
static const uint8_t u8g_dev_sh1106_128x64_init_seq_2_wire[] PROGMEM = {
U8G_ESC_ADR(0), // Initiate command mode
SH1106_ON(0), // Display off, sleep mode
SH1106_MUX_RATIO(0x3F), // Mux ratio
SH1106_DISP_OFFS(0), // Display offset
SH1106_START_LINE(0), // Start line
SH1106_ADC_REVERSE(1), // Segment remap A0/A1
SH1106_OUT_MODE(1), // 0: scan dir normal, 1: reverse
SH1106_COM_CONFIG(1), // COM pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5)
SH1106_CONTRAST(0xCF), // Set contrast control
SH1106_PAGE_ADR(0x02), // page addressing mode
SH1106_COLUMN_RANGE(2, 129), // Set column range 2 .. 129
SH1106_PAGE_RANGE(0, 7), // Set page range 0 .. 7
SH1106_CHARGE_PER(0x1, 0xF), // Pre-charge period
SH1106_VCOM_DESEL(0x40), // Vcomh deselect level
SH1106_ALL_PIX(0), // Output RAM to display
SH1106_INVERTED(0), // Normal display mode
SH1106_OSC_FREQ(0, 8), // Clock divide ratio (0:1) and oscillator frequency (8)
SH1106_CHARGE_PUMP(1), // Charge pump setting
SH1106_SCROLL(0), // Deactivate scroll
SH1106_ON(1), // Display on
U8G_ESC_END // End of sequence
U8G_ESC_ADR(0), // Initiate command mode
CMD_ON(0), // Display off, sleep mode
CMD_MUX_RATIO(0x3F), // Mux ratio
CMD_DISP_OFFS(0), // Display offset
CMD_START_LINE(0), // Start line
CMD_ADC_REVERSE(1), // Segment remap A0/A1
CMD_OUT_MODE(1), // 0: scan dir normal, 1: reverse
CMD_COM_CONFIG(1), // COM pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5)
CMD_CONTRAST(0xCF), // Set contrast control
CMD_PAGE_ADR(0x02), // page addressing mode
CMD_COLUMN_RANGE(2, 129), // Set column range 2 .. 129
CMD_PAGE_RANGE(0, 7), // Set page range 0 .. 7
CMD_CHARGE_PER(0x1, 0xF), // Pre-charge period
CMD_VCOM_DESEL(0x40), // Vcomh deselect level
CMD_ALL_PIX(0), // Output RAM to display
CMD_INVERTED(0), // Normal display mode
CMD_OSC_FREQ(0, 8), // Clock divide ratio (0:1) and oscillator frequency (8)
CMD_CHARGE_PUMP(1), // Charge pump setting
CMD_SCROLL(0), // Deactivate scroll
CMD_ON(1), // Display ON
U8G_ESC_END // End of sequence
};
uint8_t u8g_dev_sh1106_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) {
@ -142,7 +142,7 @@ uint8_t u8g_dev_sh1106_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t m
u8g_WriteEscSeqP_2_wire(u8g, dev, u8g_dev_sh1106_128x64_data_start_2_wire);
u8g_WriteByte(u8g, dev, 0xB0 | (pb->p.page*2)); // Select current page
u8g_SetAddress(u8g, dev, 1); // Data mode
u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *) pb->buf);
u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf);
u8g_SetChipSelect(u8g, dev, 0);
u8g_SetAddress(u8g, dev, 0); // Instruction mode
u8g_WriteEscSeqP_2_wire(u8g, dev, u8g_dev_sh1106_128x64_data_start_2_wire);
@ -157,39 +157,39 @@ uint8_t u8g_dev_sh1106_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t m
return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg);
}
uint8_t u8g_dev_sh1106_128x64_2x_i2c_2_wire_buf[WIDTH*2] U8G_NOCOMMON ;
u8g_pb_t u8g_dev_sh1106_128x64_2x_i2c_2_wire_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_sh1106_128x64_2x_i2c_2_wire_buf};
uint8_t u8g_dev_sh1106_128x64_2x_i2c_2_wire_buf[WIDTH * 2] U8G_NOCOMMON;
u8g_pb_t u8g_dev_sh1106_128x64_2x_i2c_2_wire_pb = { { 16, HEIGHT, 0, 0, 0 }, WIDTH, u8g_dev_sh1106_128x64_2x_i2c_2_wire_buf };
u8g_dev_t u8g_dev_sh1106_128x64_2x_i2c_2_wire = { u8g_dev_sh1106_128x64_2x_2_wire_fn, &u8g_dev_sh1106_128x64_2x_i2c_2_wire_pb, U8G_COM_SSD_I2C_HAL };
/////////////////////////////////////////////////////////////////////////////////////////////
static const uint8_t u8g_dev_ssd1306_128x64_data_start_2_wire[] PROGMEM = {
SH1106_COL_ADR(0), // Column 0
U8G_ESC_END // End of sequence
CMD_COL_ADR(0), // Column 0
U8G_ESC_END // End of sequence
};
static const uint8_t u8g_dev_ssd1306_128x64_init_seq_2_wire[] PROGMEM = {
U8G_ESC_CS(0), // Disable chip
SH1106_ON(0), // Display off, sleep mode
SH1106_MUX_RATIO(0x3F), // Mux ratio
SH1106_DISP_OFFS(0), // Display offset
SH1106_START_LINE(0), // Start line
SH1106_ADC_REVERSE(1), // Segment remap A0/A1
SH1106_OUT_MODE(1), // 0: scan dir normal, 1: reverse
SH1106_COM_CONFIG(1), // COM pin HW config, sequential com pin config (bit 4), disable left/right remap (bit 5)
SH1106_CONTRAST(0xCF), // Set contrast control
SH1106_PAGE_ADR(0x02), // page addressing mode
SH1106_COLUMN_RANGE(0, 127), // Set column range 0 .. 127
SH1106_PAGE_RANGE(0, 7), // Set page range from 0 .. 7
SH1106_CHARGE_PER(0x1, 0xF), // Pre-charge period
SH1106_VCOM_DESEL(0x40), // Vcomh deselect level
SH1106_ALL_PIX(0), // Send RAM to display
SH1106_INVERTED(0), // Normal display mode
SH1106_OSC_FREQ(0, 8), // Clock divide ratio (0:1) and oscillator frequency (8)
SH1106_CHARGE_PUMP(1), // Charge pump setting
SH1106_SCROLL(0), // Deactivate scroll
SH1106_ON(1), // Display on
U8G_ESC_END // End of sequence
U8G_ESC_CS(0), // Disable chip
CMD_ON(0), // Display OFF, sleep mode
CMD_MUX_RATIO(0x3F), // Mux ratio
CMD_DISP_OFFS(0), // Display offset
CMD_START_LINE(0), // Start line
CMD_ADC_REVERSE(1), // Segment remap A0/A1
CMD_OUT_MODE(1), // 0: scan dir normal, 1: reverse
CMD_COM_CONFIG(1), // COM pin HW config, sequential COM pin config (bit 4), disable left/right remap (bit 5)
CMD_CONTRAST(0xCF), // Set contrast control
CMD_PAGE_ADR(2), // Page addressing mode
CMD_COLUMN_RANGE(0, 127), // Set column range 0 .. 127
CMD_PAGE_RANGE(0, 7), // Set page range from 0 .. 7
CMD_CHARGE_PER(0x1, 0xF), // Pre-charge period
CMD_VCOM_DESEL(0x40), // Vcomh deselect level
CMD_ALL_PIX(0), // Send RAM to display
CMD_INVERTED(0), // Normal display mode
CMD_OSC_FREQ(0, 8), // Clock divide ratio (0:1) and oscillator frequency (8)
CMD_CHARGE_PUMP(1), // Charge pump setting
CMD_SCROLL(0), // Deactivate scroll
CMD_ON(1), // Display ON
U8G_ESC_END // End of sequence
};
uint8_t u8g_dev_ssd1306_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) {
@ -205,7 +205,7 @@ uint8_t u8g_dev_ssd1306_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t
u8g_WriteEscSeqP_2_wire(u8g, dev, u8g_dev_ssd1306_128x64_data_start_2_wire);
u8g_WriteByte(u8g, dev, 0xB0 | (pb->p.page*2)); // Select current page
u8g_SetAddress(u8g, dev, 1); // Data mode
u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *) pb->buf);
u8g_WriteSequence(u8g, dev, pb->width, (uint8_t *)pb->buf);
u8g_SetChipSelect(u8g, dev, 0);
u8g_SetAddress(u8g, dev, 0); // Instruction mode
u8g_WriteEscSeqP_2_wire(u8g, dev, u8g_dev_ssd1306_128x64_data_start_2_wire);
@ -220,8 +220,8 @@ uint8_t u8g_dev_ssd1306_128x64_2x_2_wire_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t
return u8g_dev_pb16v1_base_fn(u8g, dev, msg, arg);
}
uint8_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf[WIDTH*2] U8G_NOCOMMON ;
u8g_pb_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf};
uint8_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf[WIDTH * 2] U8G_NOCOMMON;
u8g_pb_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1306_128x64_2x_i2c_2_wire_buf };
u8g_dev_t u8g_dev_ssd1306_128x64_2x_i2c_2_wire = { u8g_dev_ssd1306_128x64_2x_2_wire_fn, &u8g_dev_ssd1306_128x64_2x_i2c_2_wire_pb, U8G_COM_SSD_I2C_HAL };
/////////////////////////////////////////////////////////////////////////////////////////////
@ -236,7 +236,7 @@ uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_s
for (;;) {
uint8_t value = u8g_pgm_read(esc_seq);
if (is_escape == 0) {
if (value != 255) {
if (value != 0xFF) {
if (u8g_WriteByte(u8g, dev, value) == 0) return 0;
if (u8g_WriteByte(u8g, dev, I2C_CMD_MODE) == 0) return 0;
}
@ -245,17 +245,17 @@ uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_s
}
}
else {
if (value == 255) {
if (value == 0xFF) {
if (u8g_WriteByte(u8g, dev, value) == 0) return 0;
if (u8g_WriteByte(u8g, dev, I2C_CMD_MODE) == 0) return 0;
}
else if (value == 254) {
else if (value == 0xFE) {
break;
}
else if (value >= 0xF0) {
// not yet used, do nothing
// Not yet used, do nothing
}
else if (value >= 0xE0 ) {
else if (value >= 0xE0) {
u8g_SetAddress(u8g, dev, value & 0x0F);
}
else if (value >= 0xD0) {
@ -270,11 +270,10 @@ uint8_t u8g_WriteEscSeqP_2_wire(u8g_t *u8g, u8g_dev_t *dev, const uint8_t *esc_s
u8g_SetResetHigh(u8g, dev);
u8g_Delay(value);
}
else if (value >= 0xBE) {
// not yet implemented
else if (value >= 0xBE) { // Not yet implemented
//u8g_SetVCC(u8g, dev, value & 0x01);
}
else if (value <= 127) {
else if (value <= 0x7F) {
u8g_Delay(value);
}
is_escape = 0;

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