mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2026-03-06 01:54:53 -07:00
Merge branch 'bugfix-2.1.x' into pr/28176
This commit is contained in:
commit
f5eeea318a
304 changed files with 2451 additions and 2028 deletions
|
|
@ -719,13 +719,13 @@
|
|||
#if ENABLED(PID_PARAMS_PER_HOTEND)
|
||||
// Specify up to one value per hotend here, according to your setup.
|
||||
// If there are fewer values, the last one applies to the remaining hotends.
|
||||
#define DEFAULT_Kp_LIST { 22.20, 22.20 }
|
||||
#define DEFAULT_Ki_LIST { 1.08, 1.08 }
|
||||
#define DEFAULT_Kd_LIST { 114.00, 114.00 }
|
||||
#define DEFAULT_KP_LIST { 22.20, 22.20 }
|
||||
#define DEFAULT_KI_LIST { 1.08, 1.08 }
|
||||
#define DEFAULT_KD_LIST { 114.00, 114.00 }
|
||||
#else
|
||||
#define DEFAULT_Kp 22.20
|
||||
#define DEFAULT_Ki 1.08
|
||||
#define DEFAULT_Kd 114.00
|
||||
#define DEFAULT_KP 22.20
|
||||
#define DEFAULT_KI 1.08
|
||||
#define DEFAULT_KD 114.00
|
||||
#endif
|
||||
#else
|
||||
#define BANG_MAX 255 // Limit hotend current while in bang-bang mode; 255=full current
|
||||
|
|
@ -823,9 +823,9 @@
|
|||
|
||||
// 120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||
// from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||
#define DEFAULT_bedKp 10.00
|
||||
#define DEFAULT_bedKi 0.023
|
||||
#define DEFAULT_bedKd 305.4
|
||||
#define DEFAULT_BED_KP 10.00
|
||||
#define DEFAULT_BED_KI 0.023
|
||||
#define DEFAULT_BED_KD 305.4
|
||||
|
||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||
#else
|
||||
|
|
@ -906,9 +906,9 @@
|
|||
|
||||
// Lasko "MyHeat Personal Heater" (200w) modified with a Fotek SSR-10DA to control only the heating element
|
||||
// and placed inside the small Creality printer enclosure tent.
|
||||
#define DEFAULT_chamberKp 37.04
|
||||
#define DEFAULT_chamberKi 1.40
|
||||
#define DEFAULT_chamberKd 655.17
|
||||
#define DEFAULT_CHAMBER_KP 37.04
|
||||
#define DEFAULT_CHAMBER_KI 1.40
|
||||
#define DEFAULT_CHAMBER_KD 655.17
|
||||
// M309 P37.04 I1.04 D655.17
|
||||
|
||||
// FIND YOUR OWN: "M303 E-2 C8 S50" to run autotune on the chamber at 50 degreesC for 8 cycles.
|
||||
|
|
|
|||
|
|
@ -415,14 +415,19 @@
|
|||
// A well-chosen Kc value should add just enough power to melt the increased material volume.
|
||||
//#define PID_EXTRUSION_SCALING
|
||||
#if ENABLED(PID_EXTRUSION_SCALING)
|
||||
#define DEFAULT_Kc (100) // heating power = Kc * e_speed
|
||||
#define LPQ_MAX_LEN 50
|
||||
#define DEFAULT_KC 100 // heating power = Kc * e_speed
|
||||
#if ENABLED(PID_PARAMS_PER_HOTEND)
|
||||
// Specify up to one value per hotend here, according to your setup.
|
||||
// If there are fewer values, the last one applies to the remaining hotends.
|
||||
#define DEFAULT_KC_LIST { DEFAULT_KC, DEFAULT_KC } // heating power = Kc * e_speed
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Add an additional term to the heater power, proportional to the fan speed.
|
||||
* A well-chosen Kf value should add just enough power to compensate for power-loss from the cooling fan.
|
||||
* You can either just add a constant compensation with the DEFAULT_Kf value
|
||||
* You can either just add a constant compensation with the DEFAULT_KF value
|
||||
* or follow the instruction below to get speed-dependent compensation.
|
||||
*
|
||||
* Constant compensation (use only with fan speeds of 0% and 100%)
|
||||
|
|
@ -453,21 +458,26 @@
|
|||
#if ENABLED(PID_FAN_SCALING_ALTERNATIVE_DEFINITION)
|
||||
// The alternative definition is used for an easier configuration.
|
||||
// Just figure out Kf at full speed (255) and PID_FAN_SCALING_MIN_SPEED.
|
||||
// DEFAULT_Kf and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly.
|
||||
// DEFAULT_KF and PID_FAN_SCALING_LIN_FACTOR are calculated accordingly.
|
||||
|
||||
#define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_Kf
|
||||
#define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_Kf
|
||||
#define PID_FAN_SCALING_AT_FULL_SPEED 13.0 //=PID_FAN_SCALING_LIN_FACTOR*255+DEFAULT_KF
|
||||
#define PID_FAN_SCALING_AT_MIN_SPEED 6.0 //=PID_FAN_SCALING_LIN_FACTOR*PID_FAN_SCALING_MIN_SPEED+DEFAULT_KF
|
||||
#define PID_FAN_SCALING_MIN_SPEED 10.0 // Minimum fan speed at which to enable PID_FAN_SCALING
|
||||
|
||||
#define DEFAULT_Kf (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED)
|
||||
#define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_Kf)/255.0
|
||||
#define DEFAULT_KF (255.0*PID_FAN_SCALING_AT_MIN_SPEED-PID_FAN_SCALING_AT_FULL_SPEED*PID_FAN_SCALING_MIN_SPEED)/(255.0-PID_FAN_SCALING_MIN_SPEED)
|
||||
#define PID_FAN_SCALING_LIN_FACTOR (PID_FAN_SCALING_AT_FULL_SPEED-DEFAULT_KF)/255.0
|
||||
|
||||
#else
|
||||
#define PID_FAN_SCALING_LIN_FACTOR (0) // Power-loss due to cooling = Kf * (fan_speed)
|
||||
#define DEFAULT_Kf 10 // A constant value added to the PID-tuner
|
||||
#define DEFAULT_KF 10 // A constant value added to the PID-tuner
|
||||
#define PID_FAN_SCALING_MIN_SPEED 10 // Minimum fan speed at which to enable PID_FAN_SCALING
|
||||
#endif
|
||||
#endif
|
||||
#if ENABLED(PID_PARAMS_PER_HOTEND)
|
||||
// Specify up to one value per hotend here, according to your setup.
|
||||
// If there are fewer values, the last one applies to the remaining hotends.
|
||||
#define DEFAULT_KF_LIST { DEFAULT_KF, DEFAULT_KF }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
@ -486,15 +496,15 @@
|
|||
#define AUTOTEMP
|
||||
#if ENABLED(AUTOTEMP)
|
||||
#define AUTOTEMP_OLDWEIGHT 0.98 // Factor used to weight previous readings (0.0 < value < 1.0)
|
||||
#define AUTOTEMP_MIN 210
|
||||
#define AUTOTEMP_MAX 250
|
||||
#define AUTOTEMP_MIN 210
|
||||
#define AUTOTEMP_MAX 250
|
||||
#define AUTOTEMP_FACTOR 0.1f
|
||||
// Turn on AUTOTEMP on M104/M109 by default using proportions set here
|
||||
//#define AUTOTEMP_PROPORTIONAL
|
||||
#if ENABLED(AUTOTEMP_PROPORTIONAL)
|
||||
#define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature
|
||||
#define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature
|
||||
#define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F)
|
||||
#define AUTOTEMP_MIN_P 0 // (°C) Added to the target temperature
|
||||
#define AUTOTEMP_MAX_P 5 // (°C) Added to the target temperature
|
||||
#define AUTOTEMP_FACTOR_P 1 // Apply this F parameter by default (overridden by M104/M109 F)
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
@ -1152,7 +1162,10 @@
|
|||
//#define FT_MOTION_MENU // Provide a MarlinUI menu to set M493 and M494 parameters
|
||||
//#define FTM_HOME_AND_PROBE // Use FT Motion for homing / probing. Disable if FT Motion breaks these functions.
|
||||
|
||||
#define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED)
|
||||
//#define FTM_DYNAMIC_FREQ // Enable for linear adjustment of XY shaping frequency according to Z or E
|
||||
#if ENABLED(FTM_DYNAMIC_FREQ)
|
||||
#define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED)
|
||||
#endif
|
||||
|
||||
#define FTM_DEFAULT_SHAPER_X ftMotionShaper_NONE // Default shaper mode on X axis (NONE, ZV, ZVD, ZVDD, ZVDDD, EI, 2HEI, 3HEI, MZV)
|
||||
#define FTM_SHAPING_DEFAULT_FREQ_X 37.0f // (Hz) Default peak frequency used by input shapers
|
||||
|
|
@ -1191,14 +1204,17 @@
|
|||
// smoothing acceleration peaks, which may also smooth curved surfaces.
|
||||
#endif
|
||||
|
||||
#define FTM_TRAJECTORY_TYPE TRAPEZOIDAL // Block acceleration profile (TRAPEZOIDAL, POLY5, POLY6)
|
||||
// TRAPEZOIDAL: Continuous Velocity. Max acceleration is respected.
|
||||
// POLY5: Like POLY6 with 1.5x but uses less CPU.
|
||||
// POLY6: Continuous Acceleration (aka S_CURVE).
|
||||
// POLY trajectories not only reduce resonances without rounding corners, but also
|
||||
// reduce extruder strain due to linear advance.
|
||||
#define FTM_POLYS // Disable POLY5/6 to save ~3k of Flash. Preserves TRAPEZOIDAL.
|
||||
#if ENABLED(FTM_POLYS)
|
||||
#define FTM_TRAJECTORY_TYPE TRAPEZOIDAL // Block acceleration profile (TRAPEZOIDAL, POLY5, POLY6)
|
||||
// TRAPEZOIDAL: Continuous Velocity. Max acceleration is respected.
|
||||
// POLY5: Like POLY6 with 1.5x but uses less CPU.
|
||||
// POLY6: Continuous Acceleration (aka S_CURVE).
|
||||
// POLY trajectories not only reduce resonances without rounding corners, but also
|
||||
// reduce extruder strain due to linear advance.
|
||||
|
||||
#define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875)
|
||||
#define FTM_POLY6_ACCELERATION_OVERSHOOT 1.875f // Max acceleration overshoot factor for POLY6 (1.25 to 1.875)
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Advanced configuration
|
||||
|
|
@ -1206,7 +1222,6 @@
|
|||
#define FTM_BUFFER_SIZE 128 // Window size for trajectory generation, must be a power of 2 (e.g 64, 128, 256, ...)
|
||||
// The total buffered time in seconds is (FTM_BUFFER_SIZE/FTM_FS)
|
||||
#define FTM_FS 1000 // (Hz) Frequency for trajectory generation.
|
||||
#define FTM_STEPPER_FS 2'000'000 // (Hz) Time resolution of stepper I/O update. Shouldn't affect CPU much (slower board testing needed)
|
||||
#define FTM_MIN_SHAPE_FREQ 20 // (Hz) Minimum shaping frequency, lower consumes more RAM
|
||||
|
||||
#endif // FT_MOTION
|
||||
|
|
@ -1784,6 +1799,14 @@
|
|||
#define PE_LEDS_COMPLETED_TIME (30*60) // (seconds) Time to keep the LED "done" color before restoring normal illumination
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Priming for the Remaining Time estimate
|
||||
* Long processes at the start of a G-code file can skew the Remaining Time estimate.
|
||||
* Enable these options to start this estimation at a later point in the G-code file.
|
||||
*/
|
||||
//#define REMAINING_TIME_PRIME // Provide G-code 'M75 R' to prime the Remaining Time estimate
|
||||
//#define REMAINING_TIME_AUTOPRIME // Prime the Remaining Time estimate later (e.g., at the end of 'M109')
|
||||
|
||||
/**
|
||||
* Continue after Power-Loss (Creality3D)
|
||||
*
|
||||
|
|
@ -1795,6 +1818,8 @@
|
|||
//#define POWER_LOSS_RECOVERY
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
#define PLR_ENABLED_DEFAULT false // Power-Loss Recovery enabled by default. (Set with 'M413 Sn' & M500)
|
||||
//#define PLR_HEAT_BED_ON_REBOOT // Heat up bed immediately on reboot to mitigate object detaching/warping.
|
||||
//#define PLR_HEAT_BED_EXTRA 0 // (°C) Relative increase of bed temperature for better adhesion (limited by max temp).
|
||||
//#define PLR_BED_THRESHOLD BED_MAXTEMP // (°C) Skip user confirmation at or above this bed temperature (0 to disable)
|
||||
|
||||
//#define POWER_LOSS_PIN 44 // Pin to detect power-loss. Set to -1 to disable default pin on boards without module, or comment to use board default.
|
||||
|
|
@ -4197,7 +4222,7 @@
|
|||
#define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing?
|
||||
#define BUTTON1_GCODE "G28"
|
||||
#define BUTTON1_DESC "Homing" // Optional string to set the LCD status
|
||||
//#define BUTTON1_IMMEDIATE // Skip the queue and run the G-code immediately. Rarely needed.
|
||||
//#define BUTTON1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed.
|
||||
#endif
|
||||
|
||||
//#define BUTTON2_PIN -1
|
||||
|
|
|
|||
|
|
@ -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-11-27"
|
||||
//#define STRING_DISTRIBUTION_DATE "2025-12-07"
|
||||
|
||||
/**
|
||||
* The protocol for communication to the host. Protocol indicates communication
|
||||
|
|
|
|||
|
|
@ -119,7 +119,6 @@ void MarlinHAL::reboot() {
|
|||
#if ENABLED(USE_WATCHDOG)
|
||||
|
||||
#include <avr/wdt.h>
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
// Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s.
|
||||
void MarlinHAL::watchdog_init() {
|
||||
|
|
@ -154,7 +153,7 @@ void MarlinHAL::reboot() {
|
|||
ISR(WDT_vect) {
|
||||
sei(); // With the interrupt driven serial we need to allow interrupts.
|
||||
SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED);
|
||||
minkill(); // interrupt-safe final kill and infinite loop
|
||||
marlin.minkill(); // interrupt-safe final kill and infinite loop
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
|||
|
|
@ -206,7 +206,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -41,7 +41,6 @@
|
|||
#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
|
||||
|
||||
#include "MarlinSerial.h"
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
#if ENABLED(DIRECT_STEPPING)
|
||||
#include "../../feature/direct_stepping.h"
|
||||
|
|
|
|||
|
|
@ -28,7 +28,7 @@
|
|||
// ------------------------
|
||||
|
||||
typedef uint16_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFU
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
|
||||
|
||||
// ------------------------
|
||||
// Defines
|
||||
|
|
@ -46,15 +46,15 @@ typedef uint16_t hal_timer_t;
|
|||
#define MF_TIMER_TEMP 0
|
||||
#endif
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY (((F_CPU) + 0x2000) / 0x4000)
|
||||
#define TEMP_TIMER_FREQUENCY (((F_CPU) + 0x2000) / 0x4000)
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_PRESCALE 8
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_PRESCALE 8
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
|
||||
|
|
|
|||
|
|
@ -27,7 +27,6 @@
|
|||
#ifdef ARDUINO_ARCH_SAM
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
#include <Wire.h>
|
||||
#include "usb/usb_task.h"
|
||||
|
|
|
|||
|
|
@ -132,7 +132,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -31,7 +31,6 @@
|
|||
|
||||
#include "MarlinSerial.h"
|
||||
#include "InterruptVectors.h"
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_r MarlinSerial<Cfg>::rx_buffer = { 0, 0, { 0 } };
|
||||
template<typename Cfg> typename MarlinSerial<Cfg>::ring_buffer_t MarlinSerial<Cfg>::tx_buffer = { 0 };
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define HAL_TIMER_PRESCALER 2
|
||||
#define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals
|
||||
|
|
@ -52,19 +52,19 @@ typedef uint32_t hal_timer_t;
|
|||
#define MF_TIMER_TONE 6 // index of timer to use for beeper tones
|
||||
#endif
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#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 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)
|
||||
|
|
|
|||
5
Marlin/src/HAL/DUE/usb/.editorconfig
Normal file
5
Marlin/src/HAL/DUE/usb/.editorconfig
Normal file
|
|
@ -0,0 +1,5 @@
|
|||
# editorconfig.org
|
||||
|
||||
[{*.c,*.cpp,*.h}]
|
||||
indent_style = tab
|
||||
indent_size = 4
|
||||
|
|
@ -194,7 +194,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -30,41 +30,46 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint64_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX)
|
||||
|
||||
#ifndef MF_TIMER_STEP
|
||||
#define MF_TIMER_STEP 0 // Timer Index for Stepper
|
||||
#endif
|
||||
#ifndef MF_TIMER_PULSE
|
||||
#define MF_TIMER_PULSE MF_TIMER_STEP
|
||||
#define MF_TIMER_PULSE MF_TIMER_STEP // Timer Index for Pulse interval
|
||||
#endif
|
||||
#ifndef MF_TIMER_TEMP
|
||||
#define MF_TIMER_TEMP 1 // Timer Index for Temperature
|
||||
#endif
|
||||
#ifndef MF_TIMER_PWM
|
||||
#define MF_TIMER_PWM 2 // index of timer to use for PWM outputs
|
||||
#define MF_TIMER_PWM 2 // Timer Index for PWM outputs
|
||||
#endif
|
||||
#ifndef MF_TIMER_TONE
|
||||
#define MF_TIMER_TONE 3 // index of timer for beeper tones
|
||||
#define MF_TIMER_TONE 3 // Timer Index for beeper tones
|
||||
#endif
|
||||
|
||||
#define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
|
||||
#define HAL_TIMER_RATE APB_CLK_FREQ // Frequency of timer peripherals
|
||||
|
||||
#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#if ENABLED(I2S_STEPPER_STREAM)
|
||||
#define STEPPER_TIMER_PRESCALE 1
|
||||
#define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock
|
||||
#define STEPPER_TIMER_RATE 250'000 // 250khz, 4µs pulses of i2s word clock
|
||||
#define STEPPER_TIMER_TICKS_PER_US 0.25 // (MHz) Stepper Timer ticks per µs
|
||||
#else
|
||||
#define STEPPER_TIMER_PRESCALE 40
|
||||
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
|
||||
#define STEPPER_TIMER_RATE ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // (Hz) Frequency of Stepper Timer ISR, 2MHz
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000UL) // (MHz) Stepper Timer ticks per µs
|
||||
#endif
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs
|
||||
|
||||
#define STEP_TIMER_MIN_INTERVAL 8 // minimum time in µs between stepper interrupts
|
||||
|
||||
#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TONE_TIMER_PRESCALE 1000 // Arbitrary value, no idea what i'm doing here
|
||||
|
||||
#define PWM_TIMER_PRESCALE 10
|
||||
#if ENABLED(FAST_PWM_FAN)
|
||||
|
|
@ -74,13 +79,9 @@ typedef uint64_t hal_timer_t;
|
|||
#endif
|
||||
#define MAX_PWM_PINS 32 // Number of PWM pin-slots
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#define 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 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)
|
||||
|
|
|
|||
|
|
@ -29,26 +29,27 @@
|
|||
// 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
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
|
||||
|
||||
extern uint32_t GetStepperTimerClkFreq();
|
||||
|
||||
// Timer configuration constants
|
||||
#define STEPPER_TIMER_RATE 2000000
|
||||
#define TEMP_TIMER_FREQUENCY 1000
|
||||
|
||||
// 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 STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
// Timer interrupt priorities
|
||||
#define STEP_TIMER_IRQ_PRIORITY 2
|
||||
|
|
|
|||
|
|
@ -67,7 +67,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms);
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -27,7 +27,7 @@
|
|||
//
|
||||
typedef Timer0 *timer_channel_t;
|
||||
typedef uint16_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFU
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
|
||||
|
||||
//
|
||||
// Timer instances
|
||||
|
|
@ -65,8 +65,8 @@ extern Timer0 step_timer;
|
|||
#define STEP_TIMER_PRIORITY DDL_IRQ_PRIORITY_00 // Top priority, nothing else uses it
|
||||
#define STEPPER_TIMER_PRESCALE 16UL // 12.5MHz
|
||||
|
||||
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz
|
||||
#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000UL) // Integer 3
|
||||
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // Integer 3
|
||||
|
||||
// Pulse timer (== stepper timer)
|
||||
#define MF_TIMER_PULSE MF_TIMER_STEP
|
||||
|
|
@ -110,11 +110,11 @@ inline void HAL_timer_isr_epilogue(const timer_channel_t) {}
|
|||
//
|
||||
// HAL function aliases
|
||||
//
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP);
|
||||
|
||||
//
|
||||
|
|
|
|||
|
|
@ -126,7 +126,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
|
||||
|
||||
|
|
@ -49,21 +49,21 @@ typedef uint32_t hal_timer_t;
|
|||
#endif
|
||||
|
||||
#define TEMP_TIMER_RATE 1000000
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -160,7 +160,7 @@ public:
|
|||
static bool watchdog_timed_out() IF_DISABLED(USE_WATCHDOG, { return false; });
|
||||
static void watchdog_clear_timeout_flag() IF_DISABLED(USE_WATCHDOG, {});
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -49,6 +49,8 @@
|
|||
|
||||
#include <Servo.h>
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
class libServo: public Servo {
|
||||
public:
|
||||
void move(const int value) {
|
||||
|
|
|
|||
|
|
@ -57,7 +57,7 @@
|
|||
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE ((F_CPU) / 4) // (Hz) Frequency of timers peripherals
|
||||
|
||||
|
|
@ -77,21 +77,19 @@ typedef uint32_t hal_timer_t;
|
|||
#define TEMP_TIMER_RATE 1000000 // 1MHz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#ifndef STEPPER_TIMER_RATE
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#endif
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -197,7 +197,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint64_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE ((SystemCoreClock) / 4) // frequency of timers peripherals
|
||||
|
||||
|
|
@ -52,22 +52,22 @@ typedef uint64_t hal_timer_t;
|
|||
#endif
|
||||
#define SYSTICK_TIMER_FREQUENCY 1000
|
||||
|
||||
#define TEMP_TIMER_RATE 1'000'000
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_RATE 1'000'000 // (Hz) Temperature Timer count rate
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR call frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1'000'000) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -32,17 +32,123 @@
|
|||
extern "C" {
|
||||
#include "pico/bootrom.h"
|
||||
#include "hardware/watchdog.h"
|
||||
#include "pico/multicore.h"
|
||||
#include "hardware/adc.h"
|
||||
#include "pico/time.h"
|
||||
}
|
||||
|
||||
#if HAS_SD_HOST_DRIVE
|
||||
#include "msc_sd.h"
|
||||
#include "usbd_cdc_if.h"
|
||||
#endif
|
||||
|
||||
// Core 1 watchdog configuration
|
||||
#define CORE1_MAX_RESETS 5 // Maximum number of Core 1 resets before halting system
|
||||
|
||||
// ------------------------
|
||||
// Public Variables
|
||||
// ------------------------
|
||||
|
||||
volatile uint32_t adc_accumulators[5] = {0}; // Accumulators for oversampling (sum of readings)
|
||||
volatile uint8_t adc_counts[5] = {0}; // Count of readings accumulated per channel
|
||||
volatile uint16_t adc_values[5] = {512, 512, 512, 512, 512}; // Final oversampled ADC values (averages) - initialized to mid-range
|
||||
|
||||
// Core 1 watchdog monitoring
|
||||
volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity
|
||||
volatile bool core1_watchdog_triggered = false; // Flag to indicate Core 1 reset
|
||||
volatile uint8_t core1_reset_count = 0; // Count of Core 1 resets - halt system if >= CORE1_MAX_RESETS
|
||||
volatile uint8_t current_pin;
|
||||
volatile bool MarlinHAL::adc_has_result;
|
||||
volatile uint8_t adc_channels_enabled[5] = {false}; // Track which ADC channels are enabled
|
||||
|
||||
// Helper function for LED blinking patterns
|
||||
void blink_led_pattern(uint8_t blink_count, uint32_t blink_duration_us = 100000) {
|
||||
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
|
||||
for (uint8_t i = 0; i < blink_count; i++) {
|
||||
WRITE(LED_PIN, HIGH);
|
||||
busy_wait_us(blink_duration_us);
|
||||
WRITE(LED_PIN, LOW);
|
||||
if (i < blink_count - 1) { // Don't delay after the last blink
|
||||
busy_wait_us(blink_duration_us);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Core 1 ADC reading task - dynamically reads all enabled channels with oversampling
|
||||
void core1_adc_task() {
|
||||
static uint32_t last_led_toggle = 0;
|
||||
const uint8_t OVERSAMPLENR = 16; // Standard Marlin oversampling count
|
||||
|
||||
// Signal successful Core 1 startup/restart
|
||||
SERIAL_ECHO_MSG("Core 1 ADC task started");
|
||||
|
||||
while (true) {
|
||||
// Update heartbeat timestamp at start of each scan cycle
|
||||
core1_last_heartbeat = time_us_32();
|
||||
|
||||
// Scan all enabled ADC channels
|
||||
for (uint8_t channel = 0; channel < 5; channel++) {
|
||||
if (!adc_channels_enabled[channel]) continue;
|
||||
|
||||
// Enable temperature sensor if reading channel 4
|
||||
if (channel == 4) {
|
||||
adc_set_temp_sensor_enabled(true);
|
||||
}
|
||||
|
||||
// Select and read the channel
|
||||
adc_select_input(channel);
|
||||
busy_wait_us(100); // Settling delay
|
||||
adc_fifo_drain();
|
||||
adc_run(true);
|
||||
|
||||
// Wait for conversion with timeout
|
||||
uint32_t timeout = 10000;
|
||||
while (adc_fifo_is_empty() && timeout--) {
|
||||
busy_wait_us(1);
|
||||
}
|
||||
|
||||
adc_run(false);
|
||||
uint16_t reading = adc_fifo_is_empty() ? 0 : adc_fifo_get();
|
||||
|
||||
// Accumulate readings for oversampling
|
||||
adc_accumulators[channel] += reading;
|
||||
adc_counts[channel]++;
|
||||
|
||||
// Update the averaged value with current accumulation (provides immediate valid data)
|
||||
adc_values[channel] = adc_accumulators[channel] / adc_counts[channel];
|
||||
|
||||
// When we reach the full oversampling count, reset accumulator for next cycle
|
||||
if (adc_counts[channel] >= OVERSAMPLENR) {
|
||||
adc_accumulators[channel] = 0;
|
||||
adc_counts[channel] = 0;
|
||||
}
|
||||
|
||||
// Disable temp sensor after reading to save power
|
||||
if (channel == 4) {
|
||||
adc_set_temp_sensor_enabled(false);
|
||||
}
|
||||
}
|
||||
|
||||
// Core 1 LED indicator: Double blink every 2 seconds to show Core 1 is active
|
||||
uint32_t now = time_us_32();
|
||||
if (now - last_led_toggle >= 2000000) { // 2 seconds
|
||||
last_led_toggle = now;
|
||||
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
|
||||
// Triple blink pattern if watchdog was triggered (shows Core 1 was reset)
|
||||
if (core1_watchdog_triggered) {
|
||||
core1_watchdog_triggered = false; // Clear flag
|
||||
blink_led_pattern(3); // Triple blink for watchdog reset
|
||||
} else {
|
||||
blink_led_pattern(2); // Normal double blink
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// Delay between full scan cycles
|
||||
busy_wait_us(10000); // 10ms between scans
|
||||
}
|
||||
}
|
||||
|
||||
volatile uint16_t adc_result;
|
||||
|
||||
// ------------------------
|
||||
|
|
@ -118,9 +224,28 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
|
|||
}
|
||||
|
||||
void MarlinHAL::watchdog_refresh() {
|
||||
// If Core 1 has reset CORE1_MAX_RESETS+ times, stop updating watchdog to halt system
|
||||
if (core1_reset_count >= CORE1_MAX_RESETS) {
|
||||
SERIAL_ECHO_MSG("Core 1 reset limit exceeded (", core1_reset_count, " resets) - halting system for safety");
|
||||
return; // Don't update watchdog - system will halt
|
||||
}
|
||||
|
||||
watchdog_update();
|
||||
|
||||
// Check Core 1 watchdog (15 second timeout)
|
||||
uint32_t now = time_us_32();
|
||||
if (now - core1_last_heartbeat > 15000000) { // 15 seconds
|
||||
// Core 1 appears stuck - reset it
|
||||
multicore_reset_core1();
|
||||
multicore_launch_core1(core1_adc_task);
|
||||
core1_watchdog_triggered = true; // Signal for LED indicator
|
||||
core1_reset_count++; // Increment reset counter
|
||||
SERIAL_ECHO_MSG("Core 1 ADC watchdog triggered - resetting Core 1 (attempt ", core1_reset_count, ")");
|
||||
}
|
||||
|
||||
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
|
||||
TOGGLE(LED_PIN); // heartbeat indicator
|
||||
// Core 0 LED indicator: Single toggle every watchdog refresh (shows Core 0 activity)
|
||||
TOGGLE(LED_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
@ -130,43 +255,35 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
|
|||
// ADC
|
||||
// ------------------------
|
||||
|
||||
volatile bool MarlinHAL::adc_has_result = false;
|
||||
|
||||
void MarlinHAL::adc_init() {
|
||||
analogReadResolution(HAL_ADC_RESOLUTION);
|
||||
::adc_init();
|
||||
adc_fifo_setup(true, false, 1, false, false);
|
||||
irq_set_exclusive_handler(ADC_IRQ_FIFO, adc_exclusive_handler);
|
||||
irq_set_enabled(ADC_IRQ_FIFO, true);
|
||||
adc_irq_set_enabled(true);
|
||||
// Launch Core 1 for continuous ADC reading
|
||||
multicore_launch_core1(core1_adc_task);
|
||||
adc_has_result = true; // Results are always available with continuous sampling
|
||||
}
|
||||
|
||||
void MarlinHAL::adc_enable(const pin_t pin) {
|
||||
if (pin >= A0 && pin <= A3)
|
||||
if (pin >= A0 && pin <= A3) {
|
||||
adc_gpio_init(pin);
|
||||
else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN)
|
||||
adc_set_temp_sensor_enabled(true);
|
||||
}
|
||||
|
||||
void MarlinHAL::adc_start(const pin_t pin) {
|
||||
adc_has_result = false;
|
||||
// Select an ADC input. 0...3 are GPIOs 26...29 respectively.
|
||||
adc_select_input(pin == HAL_ADC_MCU_TEMP_DUMMY_PIN ? 4 : pin - A0);
|
||||
adc_run(true);
|
||||
}
|
||||
|
||||
void MarlinHAL::adc_exclusive_handler() {
|
||||
adc_run(false); // Disable since we only want one result
|
||||
irq_clear(ADC_IRQ_FIFO); // Clear the IRQ
|
||||
|
||||
if (adc_fifo_get_level() >= 1) {
|
||||
adc_result = adc_fifo_get(); // Pop the result
|
||||
adc_fifo_drain();
|
||||
adc_has_result = true; // Signal the end of the conversion
|
||||
adc_channels_enabled[pin - A0] = true; // Mark this channel as enabled
|
||||
}
|
||||
else if (pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) {
|
||||
adc_channels_enabled[4] = true; // Mark MCU temp channel as enabled
|
||||
}
|
||||
}
|
||||
|
||||
uint16_t MarlinHAL::adc_value() { return adc_result; }
|
||||
void MarlinHAL::adc_start(const pin_t pin) {
|
||||
// Just store which pin we need to read - values are continuously updated by Core 1
|
||||
current_pin = pin;
|
||||
}
|
||||
|
||||
uint16_t MarlinHAL::adc_value() {
|
||||
// Return the latest ADC value from Core 1's continuous readings
|
||||
const uint8_t channel = (current_pin == HAL_ADC_MCU_TEMP_DUMMY_PIN) ? 4 : (current_pin - A0);
|
||||
return adc_values[channel];
|
||||
}
|
||||
|
||||
// Reset the system to initiate a firmware flash
|
||||
void flashFirmware(const int16_t) { hal.reboot(); }
|
||||
|
|
|
|||
|
|
@ -40,6 +40,11 @@
|
|||
#include "msc_sd.h"
|
||||
#endif
|
||||
|
||||
// ADC index 4 is the MCU temperature
|
||||
#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127
|
||||
#define TEMP_SOC_PIN HAL_ADC_MCU_TEMP_DUMMY_PIN // ADC4 is internal temp sensor
|
||||
#include "temp_soc.h"
|
||||
|
||||
//
|
||||
// Serial Ports
|
||||
//
|
||||
|
|
@ -85,8 +90,6 @@ typedef libServo hal_servo_t;
|
|||
#else
|
||||
#define HAL_ADC_RESOLUTION 12
|
||||
#endif
|
||||
// ADC index 4 is the MCU temperature
|
||||
#define HAL_ADC_MCU_TEMP_DUMMY_PIN 127
|
||||
|
||||
//
|
||||
// Pin Mapping for M42, M43, M226
|
||||
|
|
@ -141,7 +144,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() { TERN_(HAS_SD_HOST_DRIVE, tuh_task()); }
|
||||
|
||||
// Reset
|
||||
|
|
@ -164,9 +167,6 @@ public:
|
|||
// Begin ADC sampling on the given pin. Called from Temperature::isr!
|
||||
static void adc_start(const pin_t pin);
|
||||
|
||||
// This ADC runs a periodic task
|
||||
static void adc_exclusive_handler();
|
||||
|
||||
// Is the ADC ready for reading?
|
||||
static volatile bool adc_has_result;
|
||||
static bool adc_ready() { return adc_has_result; }
|
||||
|
|
|
|||
|
|
@ -44,15 +44,15 @@ static void TXBegin() {
|
|||
#endif
|
||||
}
|
||||
|
||||
static void TX(char b){
|
||||
#if SERIAL_PORT == -1
|
||||
USBSerial
|
||||
#elif SERIAL_PORT == 0
|
||||
USBSerial
|
||||
#elif SERIAL_PORT == 1
|
||||
Serial1
|
||||
#endif
|
||||
.write(b);
|
||||
static void TX(char b) {
|
||||
#if SERIAL_PORT == -1
|
||||
USBSerial
|
||||
#elif SERIAL_PORT == 0
|
||||
USBSerial
|
||||
#elif SERIAL_PORT == 1
|
||||
Serial1
|
||||
#endif
|
||||
.write(b);
|
||||
}
|
||||
|
||||
// A SW memory barrier, to ensure GCC does not overoptimize loops
|
||||
|
|
|
|||
|
|
@ -31,28 +31,48 @@
|
|||
|
||||
// NOTE: The Bigtreetech SKR Pico has an onboard W25Q16 flash module
|
||||
|
||||
// Use EEPROM.h for compatibility, for now.
|
||||
#include <EEPROM.h>
|
||||
// RP2040 Flash-based EEPROM emulation using internal flash memory
|
||||
#include <hardware/flash.h>
|
||||
#include <hardware/sync.h>
|
||||
|
||||
static bool eeprom_data_written = false;
|
||||
// Flash sector size is already defined in hardware/flash.h as FLASH_SECTOR_SIZE
|
||||
// Place EEPROM emulation at the end of flash, before the filesystem
|
||||
// This assumes 2MB flash, adjust if using different flash size
|
||||
#define FLASH_TARGET_OFFSET (PICO_FLASH_SIZE_BYTES - FLASH_SECTOR_SIZE)
|
||||
|
||||
#ifndef MARLIN_EEPROM_SIZE
|
||||
#define MARLIN_EEPROM_SIZE size_t(E2END + 1)
|
||||
#endif
|
||||
|
||||
static uint8_t eeprom_buffer[MARLIN_EEPROM_SIZE];
|
||||
static bool eeprom_data_written = false;
|
||||
static bool eeprom_initialized = false;
|
||||
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
|
||||
|
||||
bool PersistentStore::access_start() {
|
||||
EEPROM.begin(); // Avoid EEPROM.h warning (do nothing)
|
||||
eeprom_buffer_fill();
|
||||
if (!eeprom_initialized) {
|
||||
// Read from flash into buffer
|
||||
const uint8_t *flash_data = (const uint8_t *)(XIP_BASE + FLASH_TARGET_OFFSET);
|
||||
memcpy(eeprom_buffer, flash_data, MARLIN_EEPROM_SIZE);
|
||||
eeprom_initialized = true;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
bool PersistentStore::access_finish() {
|
||||
if (eeprom_data_written) {
|
||||
TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
|
||||
hal.isr_off();
|
||||
eeprom_buffer_flush();
|
||||
hal.isr_on();
|
||||
|
||||
// Disable interrupts during flash write
|
||||
const uint32_t intstate = save_and_disable_interrupts();
|
||||
|
||||
// Erase and program the sector
|
||||
flash_range_erase(FLASH_TARGET_OFFSET, FLASH_SECTOR_SIZE);
|
||||
flash_range_program(FLASH_TARGET_OFFSET, eeprom_buffer, MARLIN_EEPROM_SIZE);
|
||||
|
||||
// Restore interrupts
|
||||
restore_interrupts(intstate);
|
||||
|
||||
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
|
||||
eeprom_data_written = false;
|
||||
}
|
||||
|
|
@ -62,8 +82,8 @@ bool PersistentStore::access_finish() {
|
|||
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
|
||||
while (size--) {
|
||||
uint8_t v = *value;
|
||||
if (v != eeprom_buffered_read_byte(pos)) {
|
||||
eeprom_buffered_write_byte(pos, v);
|
||||
if (pos < (int)MARLIN_EEPROM_SIZE && v != eeprom_buffer[pos]) {
|
||||
eeprom_buffer[pos] = v;
|
||||
eeprom_data_written = true;
|
||||
}
|
||||
crc16(crc, &v, 1);
|
||||
|
|
@ -75,7 +95,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
|
|||
|
||||
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
|
||||
do {
|
||||
const uint8_t c = eeprom_buffered_read_byte(pos);
|
||||
const uint8_t c = (pos < (int)MARLIN_EEPROM_SIZE) ? eeprom_buffer[pos] : 0xFF;
|
||||
if (writing) *value = c;
|
||||
crc16(crc, &c, 1);
|
||||
pos++;
|
||||
|
|
|
|||
|
|
@ -25,7 +25,7 @@
|
|||
#include "HAL.h"
|
||||
|
||||
#ifndef NUM_DIGITAL_PINS
|
||||
#error "Expected NUM_DIGITAL_PINS not found"
|
||||
#error "Expected NUM_DIGITAL_PINS not found."
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
|
@ -74,6 +74,27 @@
|
|||
* signal. The Arduino pin number is listed by the M43 I command.
|
||||
*/
|
||||
|
||||
/**
|
||||
* Pins Debugging for RP2040
|
||||
*
|
||||
* - NUMBER_PINS_TOTAL
|
||||
* - MULTI_NAME_PAD
|
||||
* - getPinByIndex(index)
|
||||
* - printPinNameByIndex(index)
|
||||
* - getPinIsDigitalByIndex(index)
|
||||
* - digitalPinToAnalogIndex(pin)
|
||||
* - getValidPinMode(pin)
|
||||
* - isValidPin(pin)
|
||||
* - isAnalogPin(pin)
|
||||
* - digitalRead_mod(pin)
|
||||
* - pwm_status(pin)
|
||||
* - printPinPWM(pin)
|
||||
* - printPinPort(pin)
|
||||
* - printPinNumber(pin)
|
||||
* - printPinAnalog(pin)
|
||||
*/
|
||||
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define NUM_ANALOG_FIRST A0
|
||||
|
||||
#define MODE_PIN_INPUT 0 // Input mode (reset state)
|
||||
|
|
@ -81,66 +102,66 @@
|
|||
#define MODE_PIN_ALT 2 // Alternate function mode
|
||||
#define MODE_PIN_ANALOG 3 // Analog mode
|
||||
|
||||
#define PIN_NUM(P) (P & 0x000F)
|
||||
#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
|
||||
#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
|
||||
#define PORT_NUM(P) ((P >> 4) & 0x0007)
|
||||
#define PORT_ALPHA(P) ('A' + (P >> 4))
|
||||
#define getPinByIndex(x) pin_array[x].pin
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define getPinIsDigitalByIndex(x) pin_array[x].is_digital
|
||||
#define digitalPinToAnalogIndex(P) digital_pin_to_analog_pin(P)
|
||||
|
||||
/**
|
||||
* Translation of routines & variables used by pinsDebug.h
|
||||
*/
|
||||
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
|
||||
#define VALID_PIN(ANUM) (pin_t(ANUM) >= 0 && pin_t(ANUM) < NUMBER_PINS_TOTAL)
|
||||
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
|
||||
#define PRINT_PIN(Q)
|
||||
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
|
||||
uint8_t get_pin_mode(const pin_t pin) {
|
||||
// Check if pin is in alternate function mode (I2C, SPI, etc.)
|
||||
const uint32_t gpio_func = gpio_get_function(pin);
|
||||
|
||||
// x is a variable used to search pin_array
|
||||
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
|
||||
#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
|
||||
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
uint8_t get_pin_mode(const pin_t Ard_num) {
|
||||
|
||||
uint dir = gpio_get_dir( Ard_num);
|
||||
|
||||
if (dir) return MODE_PIN_OUTPUT;
|
||||
else return MODE_PIN_INPUT;
|
||||
// GPIO_FUNC_I2C is typically function 3 on RP2040
|
||||
if ( gpio_func == GPIO_FUNC_I2C
|
||||
|| gpio_func == GPIO_FUNC_SPI
|
||||
|| gpio_func == GPIO_FUNC_UART
|
||||
|| gpio_func == GPIO_FUNC_PWM
|
||||
) {
|
||||
return MODE_PIN_ALT;
|
||||
}
|
||||
|
||||
// For GPIO mode, check direction
|
||||
return gpio_get_dir(pin) ? MODE_PIN_OUTPUT : MODE_PIN_INPUT;
|
||||
}
|
||||
|
||||
bool getValidPinMode(const pin_t Ard_num) {
|
||||
const uint8_t pin_mode = get_pin_mode(Ard_num);
|
||||
bool getValidPinMode(const pin_t pin) {
|
||||
const uint8_t pin_mode = get_pin_mode(pin);
|
||||
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
|
||||
}
|
||||
|
||||
int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
|
||||
Ard_num -= NUM_ANALOG_FIRST;
|
||||
return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
|
||||
#define isValidPin(P) WITHIN(P, 0, pin_t(NUMBER_PINS_TOTAL - 1))
|
||||
|
||||
int8_t digital_pin_to_analog_pin(pin_t pin) {
|
||||
pin -= NUM_ANALOG_FIRST;
|
||||
return (WITHIN(pin, 0, NUM_ANALOG_INPUTS - 1)) ? pin : -1;
|
||||
}
|
||||
|
||||
bool isAnalogPin(const pin_t Ard_num) {
|
||||
return digital_pin_to_analog_pin(Ard_num) != -1;
|
||||
bool isAnalogPin(const pin_t pin) {
|
||||
return digital_pin_to_analog_pin(pin) != -1;
|
||||
}
|
||||
|
||||
bool is_digital(const pin_t x) {
|
||||
const uint8_t pin_mode = get_pin_mode(x);
|
||||
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
|
||||
#define digitalRead_mod(A) extDigitalRead(A) // must use Arduino pin numbers when doing reads
|
||||
#define printPinNumber(P) do{ sprintf_P(buffer, PSTR("%3d "), P); SERIAL_ECHO(buffer); }while(0)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
//bool is_digital(const pin_t pin) {
|
||||
// const uint8_t pin_mode = get_pin_mode(pin);
|
||||
// return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
|
||||
//}
|
||||
|
||||
bool pwm_status(const pin_t pin) {
|
||||
// Check if this pin is configured for PWM
|
||||
return PWM_PIN(pin) && get_pin_mode(pin) == MODE_PIN_ALT;
|
||||
}
|
||||
|
||||
void printPinPort(const pin_t Ard_num) {
|
||||
SERIAL_ECHOPGM("Pin: ");
|
||||
SERIAL_ECHO(Ard_num);
|
||||
}
|
||||
|
||||
bool pwm_status(const pin_t Ard_num) {
|
||||
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
|
||||
}
|
||||
|
||||
void printPinPWM(const pin_t Ard_num) {
|
||||
if (PWM_PIN(Ard_num)) {
|
||||
void printPinPWM(const pin_t pin) {
|
||||
if (pwm_status(pin)) {
|
||||
// RP2040 has hardware PWM on specific pins
|
||||
char buffer[22];
|
||||
sprintf_P(buffer, PSTR("PWM: pin %d "), pin);
|
||||
SERIAL_ECHO(buffer);
|
||||
}
|
||||
}
|
||||
|
||||
void printPinPort(const pin_t pin) {}
|
||||
|
|
|
|||
30
Marlin/src/HAL/RP2040/temp_soc.h
Normal file
30
Marlin/src/HAL/RP2040/temp_soc.h
Normal file
|
|
@ -0,0 +1,30 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
// RP2040 internal temperature sensor
|
||||
// Formula: T = 27 - (ADC_voltage - 0.706) / 0.001721
|
||||
// ADC_voltage = (RAW / OVERSAMPLENR) * 3.3 / 4096 (RAW is accumulated over OVERSAMPLENR samples)
|
||||
// T = 27 - ((RAW / OVERSAMPLENR) * 3.3 / 4096 - 0.706) / 0.001721
|
||||
// Simplified: T = 437.423 - (RAW / OVERSAMPLENR) * 0.46875
|
||||
|
||||
#define TEMP_SOC_SENSOR(RAW) (437.423f - ((RAW) / OVERSAMPLENR) * 0.46875f)
|
||||
|
|
@ -41,7 +41,7 @@
|
|||
#define _HAL_TIMER_ISR(T) __HAL_TIMER_ISR(T)
|
||||
|
||||
typedef uint64_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFF'FFFF'FFFF'FFFFULL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT64_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE (1'000'000ULL) // fixed value as we use a microsecond timesource
|
||||
#ifndef MF_TIMER_STEP
|
||||
|
|
@ -58,21 +58,21 @@ typedef uint64_t hal_timer_t;
|
|||
#endif
|
||||
|
||||
#define TEMP_TIMER_RATE HAL_TIMER_RATE
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE / 10 // 100khz roughly
|
||||
#define STEPPER_TIMER_TICKS_PER_US (0.1) // fixed value as we use a microsecond timesource
|
||||
#define STEPPER_TIMER_PRESCALE (10)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
28
Marlin/src/HAL/RP2040/u8g/LCD_defines.h
Normal file
28
Marlin/src/HAL/RP2040/u8g/LCD_defines.h
Normal file
|
|
@ -0,0 +1,28 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
/**
|
||||
* RP2040 LCD-specific defines
|
||||
*/
|
||||
uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr); // u8g_com_rp2040_ssd_i2c.cpp
|
||||
#define U8G_COM_SSD_I2C_HAL u8g_com_rp2040_ssd_i2c_fn
|
||||
108
Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp
Normal file
108
Marlin/src/HAL/RP2040/u8g/u8g_com_rp2040_ssd_i2c.cpp
Normal file
|
|
@ -0,0 +1,108 @@
|
|||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||
*
|
||||
* Based on Sprinter and grbl.
|
||||
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
|
||||
*
|
||||
* This program is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* This program is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* 2-Wire I2C COM Driver
|
||||
*
|
||||
* Handles Hardware I2C on valid pin combinations.
|
||||
* Wire library is used for Hardware I2C.
|
||||
*
|
||||
* Hardware I2C uses pins defined in pins_arduino.h.
|
||||
*/
|
||||
|
||||
#ifdef __PLAT_RP2040__
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_U8GLIB_I2C_OLED
|
||||
|
||||
#include <U8glib-HAL.h>
|
||||
|
||||
#include <Wire.h>
|
||||
#ifndef MASTER_ADDRESS
|
||||
#define MASTER_ADDRESS 0x01
|
||||
#endif
|
||||
|
||||
/**
|
||||
* BUFFER_LENGTH is defined in libraries\Wire\utility\WireBase.h
|
||||
* Default value is 32
|
||||
* Increase this value to 144 to send U8G_COM_MSG_WRITE_SEQ in single block
|
||||
*/
|
||||
#ifndef BUFFER_LENGTH
|
||||
#define BUFFER_LENGTH 32
|
||||
#endif
|
||||
#if BUFFER_LENGTH > 144
|
||||
#error "BUFFER_LENGTH should not be greater than 144."
|
||||
#endif
|
||||
#define I2C_MAX_LENGTH (BUFFER_LENGTH - 1)
|
||||
|
||||
uint8_t u8g_com_rp2040_ssd_i2c_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr) {
|
||||
|
||||
// Hardware I2C flag
|
||||
//static bool i2c_initialized = false; // Flag to only run init/linking code once
|
||||
//if (!i2c_initialized) { // Init runtime linkages
|
||||
// i2c_initialized = true; // Only do this once
|
||||
//}
|
||||
|
||||
static uint8_t control;
|
||||
// Use the global Wire instance (already initialized with correct pins for RP2040)
|
||||
switch (msg) {
|
||||
case U8G_COM_MSG_INIT:
|
||||
Wire.setClock(400000);
|
||||
// Wire already initialized in MarlinUI::init(), no need to call begin() again
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_ADDRESS: // Define cmd (arg_val = 0) or data mode (arg_val = 1)
|
||||
control = arg_val ? 0x40 : 0x00;
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_BYTE:
|
||||
::Wire.beginTransmission(0x3C);
|
||||
::Wire.write(control);
|
||||
::Wire.write(arg_val);
|
||||
::Wire.endTransmission();
|
||||
break;
|
||||
|
||||
case U8G_COM_MSG_WRITE_SEQ: {
|
||||
uint8_t* dataptr = (uint8_t*)arg_ptr;
|
||||
while (arg_val > 0) {
|
||||
::Wire.beginTransmission(0x3C);
|
||||
::Wire.write(control);
|
||||
if (arg_val <= I2C_MAX_LENGTH) {
|
||||
::Wire.write(dataptr, arg_val);
|
||||
arg_val = 0;
|
||||
}
|
||||
else {
|
||||
::Wire.write(dataptr, I2C_MAX_LENGTH);
|
||||
arg_val -= I2C_MAX_LENGTH;
|
||||
dataptr += I2C_MAX_LENGTH;
|
||||
}
|
||||
::Wire.endTransmission();
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
#endif // HAS_U8GLIB_I2C_OLED
|
||||
#endif // __PLAT_RP2040__
|
||||
|
|
@ -144,7 +144,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -33,7 +33,7 @@
|
|||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals
|
||||
|
||||
|
|
@ -49,15 +49,15 @@ typedef uint32_t hal_timer_t;
|
|||
#define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature
|
||||
#endif
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
|
||||
|
|
@ -143,9 +143,8 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
|
|||
Rtc * const rtc = timer_config[timer_num].pRtc;
|
||||
// Clear interrupt flag
|
||||
rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0| RTC_MODE0_INTFLAG_OVF;
|
||||
|
||||
}
|
||||
else if (timer_config[timer_num].type == TimerType::tcc){
|
||||
else if (timer_config[timer_num].type == TimerType::tcc) {
|
||||
Tcc * const tc = timer_config[timer_num].pTcc;
|
||||
// Clear interrupt flag
|
||||
tc->INTFLAG.reg = TCC_INTFLAG_OVF;
|
||||
|
|
|
|||
|
|
@ -121,7 +121,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -32,7 +32,7 @@
|
|||
// --------------------------------------------------------------------------
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE F_CPU // frequency of timers peripherals
|
||||
|
||||
|
|
@ -48,15 +48,15 @@ typedef uint32_t hal_timer_t;
|
|||
#define MF_TIMER_TEMP MF_TIMER_RTC // Timer Index for Temperature
|
||||
#endif
|
||||
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE // (Hz) Frequency of Stepper Timer ISR (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
|
||||
#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) // (MHz) Stepper Timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
|
||||
|
|
|
|||
|
|
@ -157,7 +157,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -136,10 +136,8 @@ const XrefInfo pin_xref[] PROGMEM = {
|
|||
#define printPinNumber(Q)
|
||||
#define printPinAnalog(P) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(P)); SERIAL_ECHO(buffer); }while(0)
|
||||
#define digitalPinToAnalogIndex(P) -1 // will report analog pin number in the print port routine
|
||||
|
||||
// x is a variable used to search pin_array
|
||||
#define getPinIsDigitalByIndex(x) ((bool) pin_array[x].is_digital)
|
||||
#define getPinByIndex(x) ((pin_t) pin_array[x].pin)
|
||||
#define getPinIsDigitalByIndex(x) bool(pin_array[x].is_digital)
|
||||
#define getPinByIndex(x) pin_t(pin_array[x].pin)
|
||||
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
|
||||
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
|
||||
|
||||
|
|
@ -229,8 +227,7 @@ void printPinPort(const pin_t pin) {
|
|||
calc_p -= NUM_ANALOG_FIRST;
|
||||
if (calc_p > 7) calc_p += 8;
|
||||
}
|
||||
SERIAL_ECHOPGM(" M42 P", calc_p);
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_ECHO(F(" M42 P"), calc_p, C(' '));
|
||||
if (calc_p < 100) {
|
||||
SERIAL_CHAR(' ');
|
||||
if (calc_p < 10)
|
||||
|
|
|
|||
|
|
@ -51,20 +51,20 @@
|
|||
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
|
||||
|
||||
// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
|
||||
#define STEPPER_TIMER_RATE 2000000 // 2 Mhz
|
||||
#define STEPPER_TIMER_RATE 2'000'000 // 2 Mhz
|
||||
extern uint32_t GetStepperTimerClkFreq();
|
||||
#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE))
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 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();
|
||||
|
|
|
|||
|
|
@ -187,7 +187,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask();
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -29,8 +29,6 @@ uint8_t ServoCount = 0;
|
|||
|
||||
#include "Servo.h"
|
||||
|
||||
//#include "Servo.h"
|
||||
|
||||
#include <boards.h>
|
||||
#include <io.h>
|
||||
#include <pwm.h>
|
||||
|
|
|
|||
|
|
@ -40,7 +40,7 @@
|
|||
*/
|
||||
|
||||
typedef uint16_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFU
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
|
||||
|
||||
#define HAL_TIMER_RATE uint32_t(F_CPU) // frequency of timers peripherals
|
||||
|
||||
|
|
@ -95,27 +95,27 @@ typedef uint16_t hal_timer_t;
|
|||
#define TEMP_TIMER_IRQ_PRIO 3
|
||||
#define SERVO0_TIMER_IRQ_PRIO 1
|
||||
|
||||
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
|
||||
#define TEMP_TIMER_PRESCALE 1000 // Prescaler for setting Temp Timer, 72Khz
|
||||
#define TEMP_TIMER_FREQUENCY 1000 // (Hz) Temperature ISR frequency
|
||||
|
||||
#define STEPPER_TIMER_PRESCALE 18 // prescaler for setting stepper timer, 4Mhz
|
||||
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
|
||||
#define STEPPER_TIMER_PRESCALE 18 // Prescaler for setting stepper timer, 4Mhz
|
||||
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // (Hz) Frequency of Stepper Timer ISR
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
timer_dev* HAL_get_timer_dev(int number);
|
||||
#define TIMER_DEV(num) HAL_get_timer_dev(num)
|
||||
#define STEP_TIMER_DEV TIMER_DEV(MF_TIMER_STEP)
|
||||
#define TEMP_TIMER_DEV TIMER_DEV(MF_TIMER_TEMP)
|
||||
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
|
||||
#define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
|
||||
#define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
|
||||
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
|
||||
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
|
||||
#define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
|
||||
|
||||
#define HAL_timer_get_count(timer_num) timer_get_count(TIMER_DEV(timer_num))
|
||||
|
|
|
|||
|
|
@ -142,7 +142,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -31,7 +31,5 @@ class libServo : public Servo {
|
|||
void move(const int value);
|
||||
private:
|
||||
typedef Servo super;
|
||||
uint16_t min_ticks;
|
||||
uint16_t max_ticks;
|
||||
uint8_t servoIndex; // index into the channel data for this servo
|
||||
};
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define FTM0_TIMER_PRESCALE 8
|
||||
#define FTM1_TIMER_PRESCALE 4
|
||||
|
|
@ -58,19 +58,19 @@ typedef uint32_t hal_timer_t;
|
|||
|
||||
#define TEMP_TIMER_FREQUENCY 1000
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL)
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -147,7 +147,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -35,7 +35,5 @@ class libServo : public Servo {
|
|||
void move(const int value);
|
||||
private:
|
||||
typedef Servo super;
|
||||
uint16_t min_ticks;
|
||||
uint16_t max_ticks;
|
||||
uint8_t servoIndex; // Index into the channel data for this servo
|
||||
};
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFFUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX)
|
||||
|
||||
#define FTM0_TIMER_PRESCALE 8
|
||||
#define FTM1_TIMER_PRESCALE 4
|
||||
|
|
@ -58,19 +58,19 @@ typedef uint32_t hal_timer_t;
|
|||
|
||||
#define TEMP_TIMER_FREQUENCY 1000
|
||||
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL)
|
||||
#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -160,7 +160,7 @@ public:
|
|||
|
||||
static void delay_ms(const int ms) { delay(ms); }
|
||||
|
||||
// Tasks, called from idle()
|
||||
// Tasks, called from marlin.idle()
|
||||
static void idletask() {}
|
||||
|
||||
// Reset
|
||||
|
|
|
|||
|
|
@ -37,7 +37,5 @@ class libServo : public PWMServo {
|
|||
private:
|
||||
typedef PWMServo super;
|
||||
uint8_t servoPin;
|
||||
uint16_t min_ticks;
|
||||
uint16_t max_ticks;
|
||||
uint8_t servoIndex; // Index into the channel data for this servo
|
||||
};
|
||||
|
|
|
|||
|
|
@ -34,7 +34,7 @@
|
|||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
|
||||
typedef uint32_t hal_timer_t;
|
||||
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFEUL
|
||||
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT32_MAX-1UL)
|
||||
|
||||
#define GPT_TIMER_RATE (F_CPU / 4) // 150MHz (Can't use F_BUS_ACTUAL because it's extern volatile)
|
||||
|
||||
|
|
@ -59,18 +59,18 @@ typedef uint32_t hal_timer_t;
|
|||
|
||||
#define HAL_TIMER_RATE GPT1_TIMER_RATE
|
||||
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)
|
||||
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL)
|
||||
#define STEPPER_TIMER_PRESCALE (GPT_TIMER_RATE / STEPPER_TIMER_RATE)
|
||||
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
|
||||
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
|
||||
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
|
||||
|
||||
#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_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 ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
|
||||
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
|
||||
|
||||
#ifndef HAL_STEP_TIMER_ISR
|
||||
|
|
|
|||
|
|
@ -74,11 +74,11 @@
|
|||
#endif
|
||||
|
||||
#if HAS_DWIN_E3V2
|
||||
#include "lcd/e3v2/common/encoder.h"
|
||||
#include "lcd/dwin/common/encoder.h"
|
||||
#if ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "lcd/e3v2/creality/dwin.h"
|
||||
#include "lcd/dwin/creality/dwin.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI)
|
||||
#include "lcd/e3v2/jyersui/dwin.h"
|
||||
#include "lcd/dwin/jyersui/dwin.h"
|
||||
#elif ENABLED(SOVOL_SV06_RTS)
|
||||
#include "lcd/sovol_rts/sovol_rts.h"
|
||||
#endif
|
||||
|
|
@ -160,15 +160,6 @@
|
|||
#include "feature/spindle_laser.h"
|
||||
#endif
|
||||
|
||||
#if HAS_MEDIA
|
||||
CardReader card;
|
||||
#endif
|
||||
|
||||
#if ENABLED(G38_PROBE_TARGET)
|
||||
uint8_t G38_move; // = 0
|
||||
bool G38_did_trigger; // = false
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA)
|
||||
#include "module/delta.h"
|
||||
#elif ENABLED(POLARGRAPH)
|
||||
|
|
@ -269,33 +260,51 @@
|
|||
#include "feature/rs485.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Spin in place here while keeping temperature processing alive
|
||||
*/
|
||||
void safe_delay(millis_t ms) {
|
||||
while (ms > 50) {
|
||||
ms -= 50;
|
||||
delay(50);
|
||||
thermalManager.task();
|
||||
}
|
||||
delay(ms);
|
||||
thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made
|
||||
}
|
||||
|
||||
// Singleton for Marlin global data and methods
|
||||
Marlin marlin;
|
||||
|
||||
// Marlin static data
|
||||
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
|
||||
MString<64> Marlin::machine_name;
|
||||
#endif
|
||||
|
||||
// Global state of the firmware
|
||||
MarlinState Marlin::state = MF_INITIALIZING;
|
||||
|
||||
// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop
|
||||
bool Marlin::wait_for_heatup = false;
|
||||
|
||||
#if !HAS_MEDIA
|
||||
CardReader card; // Stub instance with "no media" methods
|
||||
#endif
|
||||
|
||||
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
|
||||
bool wait_for_heatup = false;
|
||||
|
||||
// For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop
|
||||
#if HAS_RESUME_CONTINUE
|
||||
bool wait_for_user; // = false
|
||||
bool Marlin::wait_for_user; // = false
|
||||
|
||||
void wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) {
|
||||
void Marlin::wait_for_user_response(millis_t ms/*=0*/, const bool no_sleep/*=false*/) {
|
||||
UNUSED(no_sleep);
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
wait_for_user = true;
|
||||
wait_start();
|
||||
if (ms) ms += millis(); // expire time
|
||||
while (wait_for_user && !(ms && ELAPSED(millis(), ms)))
|
||||
idle(TERN_(ADVANCED_PAUSE_FEATURE, no_sleep));
|
||||
wait_for_user = false;
|
||||
user_resume();
|
||||
while (ui.button_pressed()) safe_delay(50);
|
||||
}
|
||||
|
||||
|
|
@ -325,7 +334,7 @@ bool wait_for_heatup = false;
|
|||
#pragma GCC diagnostic ignored "-Wnarrowing"
|
||||
#pragma GCC diagnostic ignored "-Wsign-compare"
|
||||
|
||||
bool pin_is_protected(const pin_t pin) {
|
||||
bool Marlin::pin_is_protected(const pin_t pin) {
|
||||
#define pgm_read_pin(P) (sizeof(pin_t) == 2 ? (pin_t)pgm_read_word(P) : (pin_t)pgm_read_byte(P))
|
||||
for (uint8_t i = 0; i < COUNT(sensitive_dio); ++i)
|
||||
if (pin == pgm_read_pin(&sensitive_dio[i])) return true;
|
||||
|
|
@ -336,28 +345,28 @@ bool pin_is_protected(const pin_t pin) {
|
|||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
bool printer_busy() {
|
||||
bool Marlin::printer_busy() {
|
||||
return planner.has_blocks_queued() || printingIsActive();
|
||||
}
|
||||
|
||||
/**
|
||||
* A Print Job exists when the timer is running or SD is printing
|
||||
*/
|
||||
bool printJobOngoing() { return print_job_timer.isRunning() || card.isStillPrinting(); }
|
||||
bool Marlin::printJobOngoing() { return print_job_timer.isRunning() || card.isStillPrinting(); }
|
||||
|
||||
/**
|
||||
* Printing is active when a job is underway but not paused
|
||||
*/
|
||||
bool printingIsActive() { return !did_pause_print && printJobOngoing(); }
|
||||
bool Marlin::printingIsActive() { return !did_pause_print && printJobOngoing(); }
|
||||
|
||||
/**
|
||||
* Printing is paused according to SD or host indicators
|
||||
*/
|
||||
bool printingIsPaused() {
|
||||
bool Marlin::printingIsPaused() {
|
||||
return did_pause_print || print_job_timer.isPaused() || card.isPaused();
|
||||
}
|
||||
|
||||
void startOrResumeJob() {
|
||||
void Marlin::startOrResumeJob() {
|
||||
if (!printingIsPaused()) {
|
||||
TERN_(GCODE_REPEAT_MARKERS, repeat.reset());
|
||||
TERN_(CANCEL_OBJECTS, cancelable.reset());
|
||||
|
|
@ -383,7 +392,7 @@ void startOrResumeJob() {
|
|||
|
||||
TERN(HAS_CUTTER, cutter.kill(), thermalManager.zero_fan_speeds()); // Full cutter shutdown including ISR control
|
||||
|
||||
wait_for_heatup = false;
|
||||
marlin.heatup_done();
|
||||
|
||||
TERN_(POWER_LOSS_RECOVERY, recovery.purge());
|
||||
|
||||
|
|
@ -395,8 +404,8 @@ void startOrResumeJob() {
|
|||
}
|
||||
|
||||
inline void finishSDPrinting() {
|
||||
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
|
||||
marlin_state = MarlinState::MF_RUNNING; // Signal to stop trying
|
||||
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
|
||||
marlin.setState(MF_RUNNING); // Signal to stop trying
|
||||
TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine());
|
||||
TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished());
|
||||
}
|
||||
|
|
@ -417,7 +426,7 @@ void startOrResumeJob() {
|
|||
* - Check if an idle but hot extruder needs filament extruded (EXTRUDER_RUNOUT_PREVENT)
|
||||
* - Pulse FET_SAFETY_PIN if it exists
|
||||
*/
|
||||
inline void manage_inactivity(const bool no_stepper_sleep=false) {
|
||||
void Marlin::manage_inactivity(const bool no_stepper_sleep/*=false*/) {
|
||||
|
||||
queue.get_available_commands();
|
||||
|
||||
|
|
@ -713,9 +722,9 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
|
|||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
// handle delayed move timeout
|
||||
if (delayed_move_time && ELAPSED(ms, delayed_move_time) && IsRunning()) {
|
||||
if (delayed_move_time && ELAPSED(ms, delayed_move_time) && isRunning()) {
|
||||
// travel moves have been received so enact them
|
||||
delayed_move_time = 0xFFFFFFFFUL; // force moves to be done
|
||||
delayed_move_time = UINT32_MAX; // force moves to be done
|
||||
destination = current_position;
|
||||
prepare_line_to_destination();
|
||||
planner.synchronize();
|
||||
|
|
@ -742,7 +751,8 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
|
|||
WRITE(FET_SAFETY_PIN, FET_SAFETY_INVERTED);
|
||||
}
|
||||
#endif
|
||||
} // manage_inactivity()
|
||||
|
||||
} // Marlin::manage_inactivity()
|
||||
|
||||
#if ALL(EP_BABYSTEPPING, EMERGENCY_PARSER)
|
||||
#include "feature/babystep.h"
|
||||
|
|
@ -770,14 +780,14 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
|
|||
* - Update the Průša MMU2
|
||||
* - Handle Joystick jogging
|
||||
*/
|
||||
void idle(const bool no_stepper_sleep/*=false*/) {
|
||||
void Marlin::idle(const bool no_stepper_sleep/*=false*/) {
|
||||
#ifdef MAX7219_DEBUG_PROFILE
|
||||
CodeProfiler idle_profiler;
|
||||
#endif
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
static uint16_t idle_depth = 0;
|
||||
if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth);
|
||||
if (++idle_depth > 5) SERIAL_ECHOLNPGM("Marlin::idle() call depth: ", idle_depth);
|
||||
#endif
|
||||
|
||||
// Bed Distance Sensor task
|
||||
|
|
@ -793,7 +803,7 @@ void idle(const bool no_stepper_sleep/*=false*/) {
|
|||
TERN_(MAX7219_DEBUG, max7219.idle_tasks());
|
||||
|
||||
// Return if setup() isn't completed
|
||||
if (marlin_state == MarlinState::MF_INITIALIZING) goto IDLE_DONE;
|
||||
if (is(MF_INITIALIZING)) goto IDLE_DONE;
|
||||
|
||||
// TODO: Still causing errors
|
||||
TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true));
|
||||
|
|
@ -893,13 +903,14 @@ void idle(const bool no_stepper_sleep/*=false*/) {
|
|||
TERN_(MARLIN_DEV_MODE, idle_depth--);
|
||||
|
||||
return;
|
||||
} // idle()
|
||||
|
||||
} // Marlin::idle()
|
||||
|
||||
/**
|
||||
* Kill all activity and lock the machine.
|
||||
* After this the machine will need to be reset.
|
||||
*/
|
||||
void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) {
|
||||
void Marlin::kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullptr*/, const bool steppers_off/*=false*/) {
|
||||
thermalManager.disable_all_heaters();
|
||||
|
||||
TERN_(HAS_CUTTER, cutter.kill()); // Full cutter shutdown including ISR control
|
||||
|
|
@ -925,7 +936,7 @@ void kill(FSTR_P const lcd_error/*=nullptr*/, FSTR_P const lcd_component/*=nullp
|
|||
minkill(steppers_off);
|
||||
}
|
||||
|
||||
void minkill(const bool steppers_off/*=false*/) {
|
||||
void Marlin::minkill(const bool steppers_off/*=false*/) {
|
||||
|
||||
// Wait a short time (allows messages to get out before shutting down.
|
||||
for (int i = 1000; i--;) DELAY_US(600);
|
||||
|
|
@ -965,13 +976,14 @@ void minkill(const bool steppers_off/*=false*/) {
|
|||
for (;;) hal.watchdog_refresh(); // Wait for RESET button or power-cycle
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
} // Marlin::minkill
|
||||
|
||||
/**
|
||||
* Turn off heaters and stop the print in progress
|
||||
* After a stop the machine may be resumed with M999
|
||||
*/
|
||||
void stop() {
|
||||
void Marlin::stop() {
|
||||
thermalManager.disable_all_heaters(); // 'unpause' taken care of in here
|
||||
|
||||
print_job_timer.stop();
|
||||
|
|
@ -980,13 +992,13 @@ void stop() {
|
|||
thermalManager.set_fans_paused(false); // Un-pause fans for safety
|
||||
#endif
|
||||
|
||||
if (!IsStopped()) {
|
||||
if (!isStopped()) {
|
||||
SERIAL_ERROR_MSG(STR_ERR_STOPPED);
|
||||
LCD_MESSAGE(MSG_STOPPED);
|
||||
safe_delay(350); // allow enough time for messages to get out before stopping
|
||||
marlin_state = MarlinState::MF_STOPPED;
|
||||
safe_delay(350); // Allow enough time for messages to get out before stopping
|
||||
setState(MF_STOPPED);
|
||||
}
|
||||
} // stop()
|
||||
} // Marlin::stop()
|
||||
|
||||
inline void tmc_standby_setup() {
|
||||
#if PIN_EXISTS(X_STDBY)
|
||||
|
|
@ -1697,7 +1709,7 @@ void setup() {
|
|||
SETUP_RUN(ftMotion.init());
|
||||
#endif
|
||||
|
||||
marlin_state = MarlinState::MF_RUNNING;
|
||||
marlin.setState(MF_RUNNING);
|
||||
|
||||
#ifdef STARTUP_TUNE
|
||||
// Play a short startup tune before continuing.
|
||||
|
|
@ -1713,7 +1725,7 @@ void setup() {
|
|||
/**
|
||||
* The main Marlin program loop
|
||||
*
|
||||
* - Call idle() to handle all tasks between G-code commands
|
||||
* - Call marlin.idle() to handle all tasks between G-code commands
|
||||
* Note that no G-codes from the queue can be executed during idle()
|
||||
* but many G-codes can be called directly anytime like macros.
|
||||
* - Check whether SD card auto-start is needed now.
|
||||
|
|
@ -1725,11 +1737,11 @@ void setup() {
|
|||
*/
|
||||
void loop() {
|
||||
do {
|
||||
idle();
|
||||
marlin.idle();
|
||||
|
||||
#if HAS_MEDIA
|
||||
if (card.flag.abort_sd_printing) abortSDPrinting();
|
||||
if (marlin_state == MarlinState::MF_SD_COMPLETE) finishSDPrinting();
|
||||
if (marlin.is(MF_SD_COMPLETE)) finishSDPrinting();
|
||||
#endif
|
||||
|
||||
queue.advance();
|
||||
|
|
|
|||
|
|
@ -27,26 +27,8 @@
|
|||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
void stop();
|
||||
|
||||
// Pass true to keep steppers from timing out
|
||||
void idle(const bool no_stepper_sleep=false);
|
||||
inline void idle_no_sleep() { idle(true); }
|
||||
|
||||
#if ENABLED(G38_PROBE_TARGET)
|
||||
extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type
|
||||
extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed
|
||||
#endif
|
||||
|
||||
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 {
|
||||
enum MarlinState : uint8_t {
|
||||
MF_INITIALIZING = 0,
|
||||
MF_STOPPED,
|
||||
MF_KILLED,
|
||||
|
|
@ -56,35 +38,81 @@ enum class MarlinState : uint8_t {
|
|||
MF_WAITING,
|
||||
};
|
||||
|
||||
extern MarlinState marlin_state;
|
||||
inline bool IsRunning() { return marlin_state >= MarlinState::MF_RUNNING; }
|
||||
inline bool IsStopped() { return marlin_state == MarlinState::MF_STOPPED; }
|
||||
typedef bool (*testFunc_t)();
|
||||
|
||||
bool printingIsActive();
|
||||
bool printJobOngoing();
|
||||
bool printingIsPaused();
|
||||
void startOrResumeJob();
|
||||
// Delay ensuring that temperatures are updated and the watchdog is kept alive
|
||||
void safe_delay(millis_t ms);
|
||||
|
||||
bool printer_busy();
|
||||
// Singleton for Marlin global data and methods
|
||||
|
||||
extern bool wait_for_heatup;
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
extern bool wait_for_user;
|
||||
void wait_for_user_response(millis_t ms=0, const bool no_sleep=false);
|
||||
#endif
|
||||
|
||||
bool pin_is_protected(const pin_t pin);
|
||||
|
||||
#if HAS_SUICIDE
|
||||
inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); }
|
||||
#endif
|
||||
|
||||
#if HAS_KILL
|
||||
#ifndef KILL_PIN_STATE
|
||||
#define KILL_PIN_STATE LOW
|
||||
class Marlin {
|
||||
public:
|
||||
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
|
||||
static MString<64> machine_name;
|
||||
#endif
|
||||
inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; }
|
||||
#endif
|
||||
|
||||
static MarlinState state;
|
||||
static void setState(const MarlinState s) { state = s; }
|
||||
static bool is(const MarlinState s) { return state == s; }
|
||||
static bool isStopped() { return is(MF_STOPPED); }
|
||||
static bool isRunning() { return state >= MF_RUNNING; }
|
||||
|
||||
static bool printingIsActive();
|
||||
static bool printJobOngoing();
|
||||
static bool printingIsPaused();
|
||||
static void startOrResumeJob();
|
||||
|
||||
static bool printer_busy();
|
||||
|
||||
static void stop();
|
||||
|
||||
// Maintain all important activities
|
||||
static void manage_inactivity(const bool no_stepper_sleep=false);
|
||||
|
||||
// Pass true to keep steppers from timing out
|
||||
static void idle(const bool no_stepper_sleep=false);
|
||||
static void idle_no_sleep() { idle(true); }
|
||||
|
||||
static void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, const bool steppers_off=false);
|
||||
static void minkill(const bool steppers_off=false);
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
// Global waiting for user response
|
||||
static bool wait_for_user;
|
||||
static void wait_start() { wait_for_user = true; }
|
||||
static void user_resume() { wait_for_user = false; }
|
||||
static void wait_for_user_response(millis_t ms=0, const bool no_sleep=false);
|
||||
#endif
|
||||
|
||||
// Global waiting for heatup state
|
||||
static bool wait_for_heatup;
|
||||
static bool is_heating() { return wait_for_heatup; }
|
||||
static void heatup_start() { wait_for_heatup = true; }
|
||||
static void heatup_done() { wait_for_heatup = false; }
|
||||
static void end_waiting() { TERN_(HAS_RESUME_CONTINUE, wait_for_user =) wait_for_heatup = false; }
|
||||
|
||||
// Shared function for M42 / M43
|
||||
static bool pin_is_protected(const pin_t pin);
|
||||
|
||||
#if HAS_SUICIDE
|
||||
static void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); }
|
||||
#endif
|
||||
|
||||
static bool kill_state() {
|
||||
return (
|
||||
#if HAS_KILL
|
||||
#ifndef KILL_PIN_STATE
|
||||
#define KILL_PIN_STATE LOW
|
||||
#endif
|
||||
READ(KILL_PIN) == KILL_PIN_STATE
|
||||
#else
|
||||
false
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
extern Marlin marlin;
|
||||
|
||||
extern const char M112_KILL_STR[];
|
||||
|
|
|
|||
|
|
@ -578,7 +578,8 @@
|
|||
//
|
||||
|
||||
#define BOARD_RP2040 6200 // Generic RP2040 Test board
|
||||
#define BOARD_BTT_SKR_PICO 6201 // BigTreeTech SKR Pico 1.x
|
||||
#define BOARD_RASPBERRY_PI_PICO 6201 // Raspberry Pi Pico
|
||||
#define BOARD_BTT_SKR_PICO 6202 // BigTreeTech SKR Pico 1.x
|
||||
|
||||
//
|
||||
// Custom board
|
||||
|
|
|
|||
|
|
@ -210,6 +210,8 @@
|
|||
#define STR_KILL_BUTTON "KILL button/pin"
|
||||
|
||||
// temperature.cpp strings
|
||||
#define STR_WAIT_FOR_HOTEND "Wait for hotend heating..."
|
||||
#define STR_WAIT_FOR_BED "Wait for bed heating..."
|
||||
#define STR_PID_AUTOTUNE "PID Autotune"
|
||||
#define STR_PID_AUTOTUNE_START " start"
|
||||
#define STR_PID_BAD_HEATER_ID " failed! Bad heater id"
|
||||
|
|
@ -230,6 +232,8 @@
|
|||
#define STR_PID_DEBUG_INPUT ": Input "
|
||||
#define STR_PID_DEBUG_OUTPUT " Output "
|
||||
#define STR_INVALID_EXTRUDER_NUM " - Invalid extruder number !"
|
||||
|
||||
// MPCTEMP strings
|
||||
#define STR_MPC_AUTOTUNE_START "MPC Autotune start for " STR_E
|
||||
#define STR_MPC_AUTOTUNE_INTERRUPTED "MPC Autotune interrupted!"
|
||||
#define STR_MPC_AUTOTUNE_FINISHED "MPC Autotune finished! Put the constants below into Configuration.h"
|
||||
|
|
@ -238,6 +242,7 @@
|
|||
#define STR_MPC_MEASURING_AMBIENT "Measuring ambient heatloss at "
|
||||
#define STR_MPC_TEMPERATURE_ERROR "Temperature error"
|
||||
|
||||
// Temperature Sensors
|
||||
#define STR_HEATER_BED "bed"
|
||||
#define STR_HEATER_CHAMBER "chamber"
|
||||
#define STR_COOLER "cooler"
|
||||
|
|
@ -247,6 +252,7 @@
|
|||
#define STR_REDUNDANT "redundant "
|
||||
#define STR_LASER_TEMP "laser temperature"
|
||||
|
||||
// Misc. Errors, Thermal Runaway
|
||||
#define STR_STOPPED_HEATER ", system stopped! Heater_ID: "
|
||||
#define STR_DETECTED_TEMP_B " (temp: "
|
||||
#define STR_DETECTED_TEMP_E ")"
|
||||
|
|
@ -269,6 +275,7 @@
|
|||
#define STR_DEBUG_COMMUNICATION "COMMUNICATION"
|
||||
#define STR_DEBUG_DETAIL "DETAIL"
|
||||
|
||||
// Password Security
|
||||
#define STR_PRINTER_LOCKED "Printer locked! (Unlock with M511 or LCD)"
|
||||
#define STR_WRONG_PASSWORD "Incorrect Password"
|
||||
#define STR_PASSWORD_TOO_LONG "Password too long"
|
||||
|
|
|
|||
|
|
@ -816,9 +816,9 @@ struct XYZval {
|
|||
FI XYZval<T>& operator-=(const XYZEval<T> &rs) { NUM_AXIS_CODE(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); return *this; }
|
||||
FI XYZval<T>& operator*=(const XYZEval<T> &rs) { NUM_AXIS_CODE(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); return *this; }
|
||||
FI XYZval<T>& operator/=(const XYZEval<T> &rs) { NUM_AXIS_CODE(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); return *this; }
|
||||
FI XYZval<T>& operator*=(const float p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZval<T>& operator*=(const float &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZval<T>& operator*=(const int &p) { NUM_AXIS_CODE(x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
|
||||
FI XYZval<T>& operator/=(const float p) { NUM_AXIS_CODE(x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; }
|
||||
FI XYZval<T>& operator/=(const float &p) { NUM_AXIS_CODE(x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; }
|
||||
FI XYZval<T>& operator>>=(const int &p) { NUM_AXIS_CODE(_RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; }
|
||||
FI XYZval<T>& operator<<=(const int &p) { NUM_AXIS_CODE(_LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; }
|
||||
|
||||
|
|
|
|||
|
|
@ -22,26 +22,16 @@
|
|||
|
||||
#include "utility.h"
|
||||
|
||||
#include "../MarlinCore.h"
|
||||
#include "../module/temperature.h"
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
MarlinError marlin_error_number; // Error Number - Marlin can beep X times periodically, display, and emit...
|
||||
#endif
|
||||
|
||||
void safe_delay(millis_t ms) {
|
||||
while (ms > 50) {
|
||||
ms -= 50;
|
||||
delay(50);
|
||||
thermalManager.task();
|
||||
}
|
||||
delay(ms);
|
||||
thermalManager.task(); // This keeps us safe if too many small safe_delay() calls are made
|
||||
}
|
||||
|
||||
// A delay to provide brittle hosts time to receive bytes
|
||||
#if ENABLED(SERIAL_OVERRUN_PROTECTION)
|
||||
|
||||
#include "../MarlinCore.h" // for safe_delay
|
||||
#include "../gcode/gcode.h" // for set_autoreport_paused
|
||||
|
||||
void serial_delay(const millis_t ms) {
|
||||
|
|
|
|||
|
|
@ -25,8 +25,6 @@
|
|||
#include "../core/types.h"
|
||||
#include "../core/millis_t.h"
|
||||
|
||||
void safe_delay(millis_t ms); // Delay ensuring that temperatures are updated and the watchdog is kept alive.
|
||||
|
||||
#if ENABLED(SERIAL_OVERRUN_PROTECTION)
|
||||
void serial_delay(const millis_t ms);
|
||||
#else
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
#if ENABLED(BABYSTEPPING)
|
||||
|
||||
#include "babystep.h"
|
||||
#include "../MarlinCore.h"
|
||||
#include "../module/motion.h" // for axis_should_home(), BABYSTEP_ALLOWED
|
||||
#include "../module/planner.h" // for axis_steps_per_mm[]
|
||||
#include "../module/stepper.h"
|
||||
|
|
|
|||
|
|
@ -24,7 +24,6 @@
|
|||
|
||||
#if ENABLED(BD_SENSOR)
|
||||
|
||||
#include "../../../MarlinCore.h"
|
||||
#include "../../../gcode/gcode.h"
|
||||
#include "../../../module/settings.h"
|
||||
#include "../../../module/motion.h"
|
||||
|
|
@ -110,7 +109,7 @@ float BDS_Leveling::read() {
|
|||
}
|
||||
|
||||
void BDS_Leveling::process() {
|
||||
if (config_state == BDS_IDLE && printingIsActive()) return;
|
||||
if (config_state == BDS_IDLE && marlin.printingIsActive()) return;
|
||||
static millis_t next_check_ms = 0; // starting at T=0
|
||||
static float zpos = 0.0f;
|
||||
const millis_t ms = millis();
|
||||
|
|
@ -156,7 +155,7 @@ void BDS_Leveling::process() {
|
|||
}
|
||||
else if (config_state == BDS_HOMING_Z) {
|
||||
SERIAL_ECHOLNPGM("Read:", tmp);
|
||||
kill(F("BDsensor connect Err!"));
|
||||
marlin.kill(F("BDsensor connect Err!"));
|
||||
}
|
||||
|
||||
DEBUG_ECHOLNPGM("BD:", tmp & 0x3FF, " Z:", cur_z, "|", current_position.z);
|
||||
|
|
|
|||
|
|
@ -28,7 +28,6 @@
|
|||
|
||||
unified_bed_leveling bedlevel;
|
||||
|
||||
#include "../../../MarlinCore.h"
|
||||
#include "../../../gcode/gcode.h"
|
||||
|
||||
#include "../../../module/settings.h"
|
||||
|
|
@ -221,7 +220,7 @@ void unified_bed_leveling::display_map(const uint8_t map_type) {
|
|||
if (human) SERIAL_CHAR(is_current ? ']' : ' ');
|
||||
|
||||
SERIAL_FLUSHTX();
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
}
|
||||
if (!lcd) SERIAL_EOL();
|
||||
|
||||
|
|
|
|||
|
|
@ -26,7 +26,6 @@
|
|||
|
||||
#include "../bedlevel.h"
|
||||
|
||||
#include "../../../MarlinCore.h"
|
||||
#include "../../../HAL/shared/eeprom_api.h"
|
||||
#include "../../../libs/hex_print.h"
|
||||
#include "../../../module/settings.h"
|
||||
|
|
@ -375,7 +374,7 @@ void unified_bed_leveling::G29() {
|
|||
bool invalidate_all = count >= GRID_MAX_POINTS;
|
||||
if (!invalidate_all) {
|
||||
while (count--) {
|
||||
if ((count & 0x0F) == 0x0F) idle();
|
||||
if ((count & 0x0F) == 0x0F) marlin.idle();
|
||||
const mesh_index_pair closest = find_closest_mesh_point_of_type(REAL, param.XY_pos);
|
||||
// No more REAL mesh points to invalidate? Assume the user meant
|
||||
// to invalidate the ENTIRE mesh, which can't be done with
|
||||
|
|
@ -856,7 +855,7 @@ void set_message_with_feedback(FSTR_P const fstr) {
|
|||
ui.quick_feedback(false); // Preserve button state for click-and-hold
|
||||
const millis_t nxt = millis() + 1500UL;
|
||||
while (ui.button_pressed()) { // Loop while the encoder is pressed. Uses hardware flag!
|
||||
idle(); // idle, of course
|
||||
marlin.idle(); // idle, of course
|
||||
if (ELAPSED(millis(), nxt)) { // After 1.5 seconds
|
||||
ui.quick_feedback();
|
||||
if (func) (*func)();
|
||||
|
|
@ -872,7 +871,7 @@ void set_message_with_feedback(FSTR_P const fstr) {
|
|||
void unified_bed_leveling::move_z_with_encoder(const float multiplier) {
|
||||
ui.wait_for_release();
|
||||
while (!ui.button_pressed()) {
|
||||
idle();
|
||||
marlin.idle();
|
||||
gcode.reset_stepper_timeout(); // Keep steppers powered
|
||||
if (encoder_diff) {
|
||||
do_blocking_move_to_z(current_position.z + float(encoder_diff) * multiplier);
|
||||
|
|
@ -1088,7 +1087,7 @@ void set_message_with_feedback(FSTR_P const fstr) {
|
|||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
|
||||
do {
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
new_z = ui.ubl_mesh_value();
|
||||
TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset + new_z)); // Move the nozzle as the point is edited
|
||||
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
|
||||
|
|
@ -1728,7 +1727,7 @@ void unified_bed_leveling::smart_fill_mesh() {
|
|||
const float ez = -lsf_results.D - lsf_results.A * ppos.x - lsf_results.B * ppos.y;
|
||||
z_values[ix][iy] = ez;
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, z_values[ix][iy]));
|
||||
idle(); // housekeeping
|
||||
marlin.idle(); // housekeeping
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
@ -1785,7 +1784,7 @@ void unified_bed_leveling::smart_fill_mesh() {
|
|||
SERIAL_EOL();
|
||||
|
||||
#if HAS_KILL
|
||||
SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", kill_state());
|
||||
SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", marlin.kill_state());
|
||||
#endif
|
||||
|
||||
SERIAL_EOL();
|
||||
|
|
@ -1823,7 +1822,7 @@ void unified_bed_leveling::smart_fill_mesh() {
|
|||
SERIAL_ECHO_MSG("EEPROM Dump:");
|
||||
persistentStore.access_start();
|
||||
for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) {
|
||||
if (!(i & 0x3)) idle();
|
||||
if (!(i & 0x3)) marlin.idle();
|
||||
print_hex_word(i);
|
||||
SERIAL_ECHOPGM(": ");
|
||||
for (uint16_t j = 0; j < 16; j++) {
|
||||
|
|
|
|||
|
|
@ -32,7 +32,6 @@
|
|||
#include "../../../module/delta.h"
|
||||
#endif
|
||||
|
||||
#include "../../../MarlinCore.h"
|
||||
#include <math.h>
|
||||
|
||||
//#define DEBUG_UBL_MOTION
|
||||
|
|
|
|||
|
|
@ -134,7 +134,7 @@ void ControllerFan::update() {
|
|||
} while (0)
|
||||
|
||||
#if ENABLED(FAN_SOFT_PWM)
|
||||
soft_pwm_speed = speed;
|
||||
soft_pwm_speed = speed >> 1; // Controller Fan Soft PWM uses 0-127 as 0-100% so cut the 0-255 range in half.
|
||||
#else
|
||||
SET_CONTROLLER_FAN();
|
||||
#if PIN_EXISTS(CONTROLLER_FAN2)
|
||||
|
|
|
|||
|
|
@ -10,7 +10,6 @@
|
|||
|
||||
#include "dac_dac084s085.h"
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../HAL/shared/Delay.h"
|
||||
|
||||
dac084s085::dac084s085() { }
|
||||
|
|
|
|||
|
|
@ -175,7 +175,7 @@ namespace DirectStepping {
|
|||
template <typename Cfg>
|
||||
void SerialPageManager<Cfg>::write_responses() {
|
||||
if (fatal_error) {
|
||||
kill(GET_TEXT_F(MSG_BAD_PAGE));
|
||||
marlin.kill(GET_TEXT_F(MSG_BAD_PAGE));
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -49,9 +49,6 @@ bool EmergencyParser::killed_by_M112, // = false
|
|||
// Global instance
|
||||
EmergencyParser emergency_parser;
|
||||
|
||||
// External references
|
||||
extern bool wait_for_user, wait_for_heatup;
|
||||
|
||||
#if ENABLED(EP_BABYSTEPPING)
|
||||
#include "babystep.h"
|
||||
#endif
|
||||
|
|
@ -208,7 +205,7 @@ void EmergencyParser::update(EmergencyParser::State &state, const uint8_t c) {
|
|||
default:
|
||||
if (ISEOL(c)) {
|
||||
if (enabled) switch (state) {
|
||||
case EP_M108: wait_for_user = wait_for_heatup = false; break;
|
||||
case EP_M108: marlin.end_waiting(); break;
|
||||
case EP_M112: killed_by_M112 = true; break;
|
||||
case EP_M410: quickstop_by_M410 = true; break;
|
||||
#if ENABLED(FTM_RESONANCE_TEST)
|
||||
|
|
|
|||
|
|
@ -86,6 +86,8 @@ public:
|
|||
|
||||
static void update(State &state, const uint8_t c);
|
||||
|
||||
static bool isEnabled() { return enabled; }
|
||||
|
||||
private:
|
||||
static bool enabled;
|
||||
};
|
||||
|
|
|
|||
|
|
@ -91,7 +91,7 @@ void EasythreedUI::blinkLED() {
|
|||
// Load/Unload buttons are a 3 position switch with a common center ground.
|
||||
//
|
||||
void EasythreedUI::loadButton() {
|
||||
if (printingIsActive()) return;
|
||||
if (marlin.printingIsActive()) return;
|
||||
|
||||
enum FilamentStatus : uint8_t { FS_IDLE, FS_PRESS, FS_CHECK, FS_PROCEED };
|
||||
static uint8_t filament_status = FS_IDLE;
|
||||
|
|
@ -185,7 +185,7 @@ void EasythreedUI::printButton() {
|
|||
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?')
|
||||
if (marlin.printingIsActive()) break; // Already printing? (find another line that checks for 'is planner doing anything else right now?')
|
||||
blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals
|
||||
print_key_flag = PF_PAUSE; // The "Print" button now pauses the print
|
||||
card.mount(); // Force SD card to mount - now!
|
||||
|
|
@ -201,13 +201,13 @@ void EasythreedUI::printButton() {
|
|||
card.openAndPrintFile(card.filename); // Start printing it
|
||||
} break;
|
||||
case PF_PAUSE: { // Pause printing (not currently firing)
|
||||
if (!printingIsActive()) break;
|
||||
if (!marlin.printingIsActive()) break;
|
||||
blink_interval_ms = LED_ON; // Set indicator to steady ON
|
||||
queue.inject(F("M25")); // Queue Pause
|
||||
print_key_flag = PF_RESUME; // The "Print" button now resumes the print
|
||||
} break;
|
||||
case PF_RESUME: { // Resume printing
|
||||
if (printingIsActive()) break;
|
||||
if (marlin.printingIsActive()) break;
|
||||
blink_interval_ms = LED_BLINK_2; // Blink the indicator LED at 1 second intervals
|
||||
queue.inject(F("M24")); // Queue resume
|
||||
print_key_flag = PF_PAUSE; // The "Print" button now pauses the print
|
||||
|
|
@ -215,7 +215,7 @@ void EasythreedUI::printButton() {
|
|||
}
|
||||
}
|
||||
else { // Register a longer press
|
||||
if (print_key_flag == PF_START && !printingIsActive()) { // While not printing, this moves Z up 10mm
|
||||
if (print_key_flag == PF_START && !marlin.printingIsActive()) { // While not printing, this moves Z up 10mm
|
||||
blink_interval_ms = LED_ON;
|
||||
queue.inject(F("G91\nG0 Z10 F600\nG90")); // Raise Z soon after returning to main loop
|
||||
}
|
||||
|
|
|
|||
|
|
@ -149,7 +149,7 @@ void I2CPositionEncoder::update() {
|
|||
|
||||
#ifdef I2CPE_ERR_THRESH_ABORT
|
||||
if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.settings.axis_steps_per_mm[encoderAxis]) {
|
||||
//kill(F("Significant Error"));
|
||||
//marlin.kill(F("Significant Error"));
|
||||
SERIAL_ECHOLNPGM("Axis error over threshold, aborting!", error);
|
||||
safe_delay(5000);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -42,30 +42,18 @@ bool FanCheck::enabled;
|
|||
|
||||
void FanCheck::init() {
|
||||
#define _TACHINIT(N) TERN(E##N##_FAN_TACHO_PULLUP, SET_INPUT_PULLUP, TERN(E##N##_FAN_TACHO_PULLDOWN, SET_INPUT_PULLDOWN, SET_INPUT))(E##N##_FAN_TACHO_PIN)
|
||||
TERF(HAS_E0_FAN_TACHO, _TACHINIT)(0);
|
||||
TERF(HAS_E1_FAN_TACHO, _TACHINIT)(1);
|
||||
TERF(HAS_E2_FAN_TACHO, _TACHINIT)(2);
|
||||
TERF(HAS_E3_FAN_TACHO, _TACHINIT)(3);
|
||||
TERF(HAS_E4_FAN_TACHO, _TACHINIT)(4);
|
||||
TERF(HAS_E5_FAN_TACHO, _TACHINIT)(5);
|
||||
TERF(HAS_E6_FAN_TACHO, _TACHINIT)(6);
|
||||
TERF(HAS_E7_FAN_TACHO, _TACHINIT)(7);
|
||||
#define _EN_TACHINIT(N) TERF(HAS_E##N##_FAN_TACHO, _TACHINIT)(N);
|
||||
REPEAT(8, _EN_TACHINIT);
|
||||
}
|
||||
|
||||
void FanCheck::update_tachometers() {
|
||||
bool status;
|
||||
|
||||
#define _TACHO_CASE(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break;
|
||||
#define __TACHO_GET_STATUS(N) case N: status = READ(E##N##_FAN_TACHO_PIN); break;
|
||||
#define _TACHO_GET_STATUS(N) TERF(HAS_E##N##_FAN_TACHO, __TACHO_GET_STATUS)(N)
|
||||
for (uint8_t f = 0; f < TACHO_COUNT; ++f) {
|
||||
switch (f) {
|
||||
TERF(HAS_E0_FAN_TACHO, _TACHO_CASE)(0)
|
||||
TERF(HAS_E1_FAN_TACHO, _TACHO_CASE)(1)
|
||||
TERF(HAS_E2_FAN_TACHO, _TACHO_CASE)(2)
|
||||
TERF(HAS_E3_FAN_TACHO, _TACHO_CASE)(3)
|
||||
TERF(HAS_E4_FAN_TACHO, _TACHO_CASE)(4)
|
||||
TERF(HAS_E5_FAN_TACHO, _TACHO_CASE)(5)
|
||||
TERF(HAS_E6_FAN_TACHO, _TACHO_CASE)(6)
|
||||
TERF(HAS_E7_FAN_TACHO, _TACHO_CASE)(7)
|
||||
REPEAT(8, _TACHO_GET_STATUS)
|
||||
default: continue;
|
||||
}
|
||||
|
||||
|
|
@ -83,14 +71,8 @@ void FanCheck::compute_speed(uint16_t elapsedTime) {
|
|||
uint8_t fan_error_msk = 0;
|
||||
for (uint8_t f = 0; f < TACHO_COUNT; ++f) {
|
||||
switch (f) {
|
||||
TERN_(HAS_E0_FAN_TACHO, case 0:)
|
||||
TERN_(HAS_E1_FAN_TACHO, case 1:)
|
||||
TERN_(HAS_E2_FAN_TACHO, case 2:)
|
||||
TERN_(HAS_E3_FAN_TACHO, case 3:)
|
||||
TERN_(HAS_E4_FAN_TACHO, case 4:)
|
||||
TERN_(HAS_E5_FAN_TACHO, case 5:)
|
||||
TERN_(HAS_E6_FAN_TACHO, case 6:)
|
||||
TERN_(HAS_E7_FAN_TACHO, case 7:)
|
||||
#define _EN_COMPUTE_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:)
|
||||
REPEAT(8, _EN_COMPUTE_FAN_CASE)
|
||||
// Compute fan speed
|
||||
rps[f] = edge_counter[f] * float(250) / elapsedTime;
|
||||
edge_counter[f] = 0;
|
||||
|
|
@ -111,7 +93,7 @@ void FanCheck::compute_speed(uint16_t elapsedTime) {
|
|||
// Drop the error when all fans are ok
|
||||
if (!fan_error_msk && error == TachoError::REPORTED) error = TachoError::FIXED;
|
||||
|
||||
if (error == TachoError::FIXED && !printJobOngoing() && !printingIsPaused()) {
|
||||
if (error == TachoError::FIXED && !marlin.printJobOngoing() && !marlin.printingIsPaused()) {
|
||||
error = TachoError::NONE; // if the issue has been fixed while the printer is idle, reenable immediately
|
||||
ui.reset_alert_level();
|
||||
}
|
||||
|
|
@ -124,17 +106,17 @@ void FanCheck::compute_speed(uint16_t elapsedTime) {
|
|||
}
|
||||
|
||||
void FanCheck::report_speed_error(uint8_t fan) {
|
||||
if (printJobOngoing()) {
|
||||
if (marlin.printJobOngoing()) {
|
||||
if (error == TachoError::NONE) {
|
||||
if (thermalManager.degTargetHotend(fan) != 0) {
|
||||
kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT));
|
||||
marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT));
|
||||
error = TachoError::REPORTED;
|
||||
}
|
||||
else
|
||||
error = TachoError::DETECTED; // Plans error for next processed command
|
||||
}
|
||||
}
|
||||
else if (!printingIsPaused()) {
|
||||
else if (!marlin.printingIsPaused()) {
|
||||
thermalManager.setTargetHotend(0, fan); // Always disable heating
|
||||
if (error == TachoError::NONE) error = TachoError::REPORTED;
|
||||
}
|
||||
|
|
@ -147,14 +129,8 @@ void FanCheck::print_fan_states() {
|
|||
for (uint8_t s = 0; s < 2; ++s) {
|
||||
for (uint8_t f = 0; f < TACHO_COUNT; ++f) {
|
||||
switch (f) {
|
||||
TERN_(HAS_E0_FAN_TACHO, case 0:)
|
||||
TERN_(HAS_E1_FAN_TACHO, case 1:)
|
||||
TERN_(HAS_E2_FAN_TACHO, case 2:)
|
||||
TERN_(HAS_E3_FAN_TACHO, case 3:)
|
||||
TERN_(HAS_E4_FAN_TACHO, case 4:)
|
||||
TERN_(HAS_E5_FAN_TACHO, case 5:)
|
||||
TERN_(HAS_E6_FAN_TACHO, case 6:)
|
||||
TERN_(HAS_E7_FAN_TACHO, case 7:)
|
||||
#define _EN_PRINT_FAN_CASE(N) TERN_(HAS_E##N##_FAN_TACHO, case N:)
|
||||
REPEAT(8, _EN_PRINT_FAN_CASE)
|
||||
SERIAL_ECHOPGM("E", f);
|
||||
if (s == 0)
|
||||
SERIAL_ECHOPGM(":", 60 * rps[f], " RPM ");
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
|
||||
#if HAS_FANCHECK
|
||||
|
||||
#include "../MarlinCore.h"
|
||||
#include "../lcd/marlinui.h"
|
||||
|
||||
#if ENABLED(AUTO_REPORT_FANS)
|
||||
|
|
@ -74,7 +73,11 @@ class FanCheck {
|
|||
static void check_deferred_error() {
|
||||
if (error == TachoError::DETECTED) {
|
||||
error = TachoError::REPORTED;
|
||||
TERN(PARK_HEAD_ON_PAUSE, queue.inject(F("M125")), kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT)));
|
||||
#if ENABLED(PARK_HEAD_ON_PAUSE)
|
||||
queue.inject(F("M125"));
|
||||
#else
|
||||
marlin.kill(GET_TEXT_F(MSG_FAN_SPEED_FAULT));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -87,10 +87,6 @@ void HostUI::action(FSTR_P const fstr, const bool eol) {
|
|||
PGMSTR(CONTINUE_STR, "Continue");
|
||||
PGMSTR(DISMISS_STR, "Dismiss");
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
extern bool wait_for_user;
|
||||
#endif
|
||||
|
||||
void HostUI::notify(const char * const cstr) {
|
||||
PORT_REDIRECT(SerialMask::All);
|
||||
action(F("notification "), false);
|
||||
|
|
@ -205,7 +201,7 @@ void HostUI::action(FSTR_P const fstr, const bool eol) {
|
|||
}
|
||||
break;
|
||||
case PROMPT_USER_CONTINUE:
|
||||
TERN_(HAS_RESUME_CONTINUE, wait_for_user = false);
|
||||
TERN_(HAS_RESUME_CONTINUE, marlin.user_resume());
|
||||
break;
|
||||
case PROMPT_PAUSE_RESUME:
|
||||
#if ALL(ADVANCED_PAUSE_FEATURE, HAS_MEDIA)
|
||||
|
|
|
|||
|
|
@ -43,7 +43,7 @@ millis_t HotendIdleProtection::next_protect_ms = 0;
|
|||
hotend_idle_settings_t HotendIdleProtection::cfg; // Initialized by settings.load
|
||||
|
||||
void HotendIdleProtection::check_hotends(const millis_t &ms) {
|
||||
const bool busy = (TERN0(HAS_RESUME_CONTINUE, wait_for_user) || planner.has_blocks_queued());
|
||||
const bool busy = (TERN0(HAS_RESUME_CONTINUE, marlin.wait_for_user) || planner.has_blocks_queued());
|
||||
bool do_prot = false;
|
||||
if (!busy && cfg.timeout != 0) {
|
||||
HOTEND_LOOP() {
|
||||
|
|
|
|||
|
|
@ -74,14 +74,13 @@
|
|||
|
||||
#ifdef MAX7219_DEBUG_PROFILE
|
||||
// This class sums up the amount of time for which its instances exist.
|
||||
// By default there is one instantiated for the duration of the idle()
|
||||
// function. But an instance can be created in any code block to measure
|
||||
// the time spent from the point of instantiation until the CPU leaves
|
||||
// block. Be careful about having multiple instances of CodeProfiler as
|
||||
// it does not guard against double counting. In general mixing ISR and
|
||||
// non-ISR use will require critical sections but note that mode setting
|
||||
// is atomic so the total or average times can safely be read if you set
|
||||
// mode to FREEZE first.
|
||||
// By default there is one instantiated for the duration of marlin.idle()
|
||||
// but an instance can be created in any code block to measure time spent
|
||||
// from instantiation until the CPU leaves the block.
|
||||
// Be careful about having multiple instances of CodeProfiler as it does
|
||||
// not guard against double counting. In general mixing ISR and non-ISR
|
||||
// use will require critical sections but note that mode setting is atomic
|
||||
// so the total or average times can safely be read if you set mode to FREEZE first.
|
||||
class CodeProfiler {
|
||||
public:
|
||||
enum Mode : uint8_t { ACCUMULATE_AVERAGE, ACCUMULATE_TOTAL, FREEZE };
|
||||
|
|
|
|||
|
|
@ -24,7 +24,6 @@
|
|||
|
||||
#if HAS_PRUSA_MMU1
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
|
|
|
|||
|
|
@ -40,7 +40,6 @@ MMU2 mmu2;
|
|||
#include "../../module/temperature.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../MarlinCore.h"
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
#include "../host_actions.h"
|
||||
|
|
@ -446,7 +445,7 @@ bool MMU2::rx_ok() {
|
|||
void MMU2::check_version(const uint16_t buildnr) {
|
||||
if (buildnr < MMU_REQUIRED_FW_BUILDNR) {
|
||||
SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required.");
|
||||
kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE));
|
||||
marlin.kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE));
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -786,10 +785,10 @@ void MMU2::command(const uint8_t mmu_cmd) {
|
|||
* Wait for response from MMU
|
||||
*/
|
||||
bool MMU2::get_response() {
|
||||
while (cmd != MMU_CMD_NONE) idle();
|
||||
while (cmd != MMU_CMD_NONE) marlin.idle();
|
||||
|
||||
while (!ready) {
|
||||
idle();
|
||||
marlin.idle();
|
||||
if (state != 3) break;
|
||||
}
|
||||
|
||||
|
|
@ -985,7 +984,7 @@ bool MMU2::eject_filament(const uint8_t index, const bool recover) {
|
|||
mmu2_attn_buzz();
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER)));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_MMU2_EJECT_RECOVER)));
|
||||
TERN_(HAS_RESUME_CONTINUE, wait_for_user_response());
|
||||
TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response());
|
||||
mmu2_attn_buzz();
|
||||
|
||||
command(MMU_CMD_R0);
|
||||
|
|
|
|||
|
|
@ -274,7 +274,7 @@ namespace MMU3 {
|
|||
*/
|
||||
void MMU3::checkFINDARunout() {
|
||||
if (!findaDetectsFilament()
|
||||
//&& printJobOngoing()
|
||||
//&& marlin.printJobOngoing()
|
||||
&& parser.codenum != 600
|
||||
&& TERN1(HAS_LEVELING, planner.leveling_active)
|
||||
&& xy_are_trusted()
|
||||
|
|
@ -857,7 +857,7 @@ namespace MMU3 {
|
|||
for (;;) {
|
||||
// in our new implementation, we know the exact state of the MMU at any moment, we do not have to wait for a timeout
|
||||
// So in this case we should decide if the operation is:
|
||||
// - still running -> wait normally in idle()
|
||||
// - still running -> wait normally in marlin.idle()
|
||||
// - failed -> then do the safety moves on the printer like before
|
||||
// - finished ok -> proceed with reading other commands
|
||||
safe_delay_keep_alive(0); // calls logicStep() and remembers its return status
|
||||
|
|
|
|||
|
|
@ -122,15 +122,15 @@ namespace MMU3 {
|
|||
#endif
|
||||
}
|
||||
|
||||
bool marlin_printingIsActive() { return printingIsActive(); }
|
||||
bool marlin_printingIsActive() { return marlin.printingIsActive(); }
|
||||
|
||||
void marlin_manage_heater() { thermalManager.task(); }
|
||||
|
||||
void marlin_manage_inactivity(const bool b) { idle(b); }
|
||||
void marlin_manage_inactivity(const bool b) { marlin.idle(b); }
|
||||
|
||||
void marlin_idle(bool b) {
|
||||
void marlin_idle(const bool b) {
|
||||
thermalManager.task();
|
||||
idle(b);
|
||||
marlin.idle(b);
|
||||
}
|
||||
|
||||
void marlin_refresh_print_state_in_ram() {
|
||||
|
|
@ -157,7 +157,7 @@ namespace MMU3 {
|
|||
void thermal_setTargetHotend(int16_t t) { thermalManager.setTargetHotend(t, 0); }
|
||||
|
||||
void safe_delay_keep_alive(uint16_t t) {
|
||||
idle(true);
|
||||
marlin.idle(true);
|
||||
safe_delay(t);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -213,7 +213,7 @@ namespace MMU3 {
|
|||
|
||||
void EndReport(CommandInProgress /*cip*/, ProgressCode /*ec*/) {
|
||||
// clear the status msg line - let the printed filename get visible again
|
||||
if (!printJobOngoing()) ui.reset_status();
|
||||
if (!marlin.printJobOngoing()) ui.reset_status();
|
||||
//custom_message_type = CustomMsg::Status;
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -187,7 +187,7 @@
|
|||
}
|
||||
// Wait for 5 seconds before displaying the next text.
|
||||
for (uint8_t i = 0; i < 100; ++i) {
|
||||
idle(true);
|
||||
marlin.idle(true);
|
||||
safe_delay(50);
|
||||
if (ui.use_click()) {
|
||||
if (fmsg_next == nullptr) {
|
||||
|
|
|
|||
|
|
@ -160,10 +160,10 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P
|
|||
if (wait) return thermalManager.wait_for_hotend(active_extruder);
|
||||
|
||||
// Allow interruption by Emergency Parser M108
|
||||
wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude);
|
||||
while (wait_for_heatup && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW))
|
||||
idle();
|
||||
wait_for_heatup = false;
|
||||
marlin.wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude);
|
||||
while (marlin.is_heating() && ABS(thermalManager.wholeDegHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > (TEMP_WINDOW))
|
||||
marlin.idle();
|
||||
marlin.heatup_done();
|
||||
|
||||
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||
// A user can cancel wait-for-heating with M108
|
||||
|
|
@ -206,7 +206,7 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len
|
|||
first_impatient_beep(max_beep_count);
|
||||
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
wait_for_user = true; // LCD click or M108 will clear this
|
||||
marlin.wait_start(); // LCD click or M108 will clear this
|
||||
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENTLOAD)));
|
||||
|
||||
|
|
@ -215,19 +215,19 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len
|
|||
hostui.prompt_do(PROMPT_USER_CONTINUE, F("Load Filament T"), tool, FPSTR(CONTINUE_STR));
|
||||
#endif
|
||||
|
||||
while (wait_for_user) {
|
||||
while (marlin.wait_for_user) {
|
||||
impatient_beep(max_beep_count);
|
||||
#if ALL(HAS_FILAMENT_SENSOR, FILAMENT_CHANGE_RESUME_ON_INSERT)
|
||||
#if MULTI_FILAMENT_SENSOR
|
||||
#define _CASE_INSERTED(N) case N-1: if (!FILAMENT_IS_OUT(N)) wait_for_user = false; break;
|
||||
#define _CASE_INSERTED(N) case N-1: if (!FILAMENT_IS_OUT(N)) marlin.user_resume(); break;
|
||||
switch (active_extruder) {
|
||||
REPEAT_1(NUM_RUNOUT_SENSORS, _CASE_INSERTED)
|
||||
}
|
||||
#else
|
||||
if (!FILAMENT_IS_OUT()) wait_for_user = false;
|
||||
if (!FILAMENT_IS_OUT()) marlin.user_resume();
|
||||
#endif
|
||||
#endif
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -270,10 +270,10 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len
|
|||
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)));
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_FILAMENT_CHANGE_PURGE)));
|
||||
wait_for_user = true; // A click or M108 breaks the purge_length loop
|
||||
for (float purge_count = purge_length; purge_count > 0 && wait_for_user; --purge_count)
|
||||
marlin.wait_start(); // A click or M108 breaks the purge_length loop
|
||||
for (float purge_count = purge_length; purge_count > 0 && marlin.wait_for_user; --purge_count)
|
||||
unscaled_e_move(1, ADVANCED_PAUSE_PURGE_FEEDRATE);
|
||||
wait_for_user = false;
|
||||
marlin.user_resume();
|
||||
|
||||
#else
|
||||
|
||||
|
|
@ -297,14 +297,14 @@ bool load_filament(const float slow_load_length/*=0*/, const float fast_load_len
|
|||
if (show_lcd) {
|
||||
// Show "Purge More" / "Resume" menu and wait for reply
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
wait_for_user = false;
|
||||
marlin.user_resume();
|
||||
pause_menu_response = PAUSE_RESPONSE_WAIT_FOR;
|
||||
#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI)
|
||||
ui.pause_show_message(PAUSE_MESSAGE_OPTION); // MarlinUI and MKS UI also set PAUSE_RESPONSE_WAIT_FOR
|
||||
#else
|
||||
pause_menu_response = PAUSE_RESPONSE_WAIT_FOR;
|
||||
TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_PurgeMore_L, ID_PurgeMore_D));
|
||||
#endif
|
||||
while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep();
|
||||
while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) marlin.idle_no_sleep();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
@ -553,8 +553,8 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
|
|||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(GET_TEXT_F(MSG_NOZZLE_PARKED)));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_NOZZLE_PARKED)));
|
||||
wait_for_user = true; // LCD click or M108 will clear this
|
||||
while (wait_for_user) {
|
||||
marlin.wait_start(); // LCD click or M108 will clear this
|
||||
while (marlin.wait_for_user) {
|
||||
impatient_beep(max_beep_count);
|
||||
|
||||
// If the nozzle has timed out...
|
||||
|
|
@ -579,7 +579,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
|
|||
ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_HEATER_TIMEOUT));
|
||||
#endif
|
||||
|
||||
TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(0, true)); // Wait for LCD click or M108
|
||||
TERN_(HAS_RESUME_CONTINUE, marlin.wait_for_user_response(0, true)); // Wait for LCD click or M108
|
||||
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_INFO, GET_TEXT_F(MSG_REHEATING)));
|
||||
|
||||
|
|
@ -606,12 +606,12 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
|
|||
LCD_MESSAGE(MSG_REHEATDONE);
|
||||
#endif
|
||||
|
||||
IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, wait_for_user = true);
|
||||
IF_DISABLED(PAUSE_REHEAT_FAST_RESUME, marlin.wait_start());
|
||||
|
||||
nozzle_timed_out = false;
|
||||
first_impatient_beep(max_beep_count);
|
||||
}
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
}
|
||||
TERN_(DUAL_X_CARRIAGE, set_duplication_enabled(saved_ext_dup_mode, saved_ext));
|
||||
}
|
||||
|
|
|
|||
|
|
@ -119,7 +119,7 @@ void Power::power_on() {
|
|||
* Processes any PSU_POWEROFF_GCODE and makes a PS_OFF_SOUND if enabled.
|
||||
*/
|
||||
void Power::power_off() {
|
||||
TERN_(HAS_SUICIDE, suicide());
|
||||
TERN_(HAS_SUICIDE, marlin.suicide());
|
||||
|
||||
if (!psu_on) return;
|
||||
|
||||
|
|
@ -208,7 +208,7 @@ void Power::power_off() {
|
|||
// If any of the stepper drivers are enabled...
|
||||
if (stepper.axis_enabled.bits) return true;
|
||||
|
||||
if (printJobOngoing() || printingIsPaused()) return true;
|
||||
if (marlin.printJobOngoing() || marlin.printingIsPaused()) return true;
|
||||
|
||||
#if ENABLED(AUTO_POWER_FANS)
|
||||
FANS_LOOP(i) if (thermalManager.fan_speed[i]) return true;
|
||||
|
|
|
|||
|
|
@ -141,6 +141,14 @@ bool PrintJobRecovery::check() {
|
|||
return success;
|
||||
}
|
||||
|
||||
/**
|
||||
* Cancel recovery
|
||||
*/
|
||||
void PrintJobRecovery::cancel() {
|
||||
TERN_(PLR_HEAT_BED_ON_REBOOT, set_bed_temp(false));
|
||||
purge();
|
||||
}
|
||||
|
||||
/**
|
||||
* Delete the recovery file and clear the recovery data
|
||||
*/
|
||||
|
|
@ -313,7 +321,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW
|
|||
void PrintJobRecovery::_outage(TERN_(DEBUG_POWER_LOSS_RECOVERY, const bool simulated/*=false*/)) {
|
||||
#if ENABLED(BACKUP_POWER_SUPPLY)
|
||||
static bool lock = false;
|
||||
if (lock) return; // No re-entrance from idle() during retract_and_lift()
|
||||
if (lock) return; // No re-entrance from marlin.idle() during retract_and_lift()
|
||||
lock = true;
|
||||
#endif
|
||||
|
||||
|
|
@ -347,7 +355,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW
|
|||
sync_plan_position();
|
||||
}
|
||||
else
|
||||
kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY));
|
||||
marlin.kill(GET_TEXT_F(MSG_OUTAGE_RECOVERY));
|
||||
}
|
||||
|
||||
#endif // POWER_LOSS_PIN || DEBUG_POWER_LOSS_RECOVERY
|
||||
|
|
@ -366,6 +374,13 @@ void PrintJobRecovery::write() {
|
|||
if (!file.close()) DEBUG_ECHOLNPGM("Power-loss file close failed.");
|
||||
}
|
||||
|
||||
#if ENABLED(PLR_HEAT_BED_ON_REBOOT)
|
||||
// Set bed temperature and wait. Called from M1000 to resume bed heating.
|
||||
void PrintJobRecovery::set_bed_temp(const bool on) {
|
||||
PROCESS_SUBCOMMANDS_NOW(TS(F("M190S"), on ? info.target_temperature_bed + PLR_HEAT_BED_EXTRA : 0));
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Resume the saved print job
|
||||
*/
|
||||
|
|
|
|||
|
|
@ -201,10 +201,15 @@ class PrintJobRecovery {
|
|||
static void close() { file.close(); }
|
||||
|
||||
static bool check();
|
||||
|
||||
#if ENABLED(PLR_HEAT_BED_ON_REBOOT)
|
||||
static void set_bed_temp(const bool turn_on);
|
||||
#endif
|
||||
|
||||
static void resume();
|
||||
static void purge();
|
||||
|
||||
static void cancel() { purge(); }
|
||||
static void cancel();
|
||||
|
||||
static void load();
|
||||
static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false);
|
||||
|
|
|
|||
|
|
@ -31,7 +31,6 @@
|
|||
#include "../module/stepper.h" // for block_t
|
||||
#include "../gcode/queue.h"
|
||||
#include "pause.h" // for did_pause_print
|
||||
#include "../MarlinCore.h" // for printingIsActive()
|
||||
|
||||
#include "../inc/MarlinConfig.h"
|
||||
|
||||
|
|
@ -64,7 +63,7 @@ typedef Flags<
|
|||
> runout_flags_t;
|
||||
|
||||
void event_filament_runout(const uint8_t extruder);
|
||||
inline bool should_monitor_runout() { return did_pause_print || printingIsActive(); }
|
||||
inline bool should_monitor_runout() { return did_pause_print || marlin.printingIsActive(); }
|
||||
|
||||
template<class RESPONSE_T, class SENSOR_T>
|
||||
class TFilamentMonitor;
|
||||
|
|
|
|||
|
|
@ -112,7 +112,7 @@ void SpindleLaser::init() {
|
|||
const millis_t duration = (float(SPEED_POWER_MAX) * (60000.f / 2550.f) / float(acceleration_spindle_deg_per_s2)) * abs_diff;
|
||||
millis_t next_ocr_change = millis() + duration;
|
||||
while (current_ocr != ocr) {
|
||||
while (PENDING(millis(), next_ocr_change)) idle();
|
||||
while (PENDING(millis(), next_ocr_change)) marlin.idle();
|
||||
current_ocr += diff > 0 ? 1 : -1;
|
||||
hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), current_ocr ^ SPINDLE_LASER_PWM_OFF);
|
||||
next_ocr_change += duration;
|
||||
|
|
|
|||
|
|
@ -31,7 +31,6 @@
|
|||
*/
|
||||
|
||||
#include "tmc_util.h"
|
||||
#include "../MarlinCore.h"
|
||||
|
||||
#include "../module/stepper/indirection.h"
|
||||
#include "../module/printcounter.h"
|
||||
|
|
@ -283,7 +282,7 @@
|
|||
if (data.is_s2g) SERIAL_ECHOLNPGM("coil short circuit");
|
||||
TERN_(TMC_DEBUG, tmc_report_all());
|
||||
TERN_(SOVOL_SV06_RTS, rts.gotoPage(ID_DriverError_L, ID_DriverError_D));
|
||||
kill(F("Driver error"));
|
||||
marlin.kill(F("Driver error"));
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
|||
|
|
@ -105,7 +105,6 @@
|
|||
#include "../gcode.h"
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/tool_change.h"
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
#if HAS_MESH
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for IsRunning()
|
||||
#include "../../module/motion.h"
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
|
||||
|
|
|
|||
|
|
@ -51,7 +51,7 @@
|
|||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "../../../lcd/e3v2/creality/dwin.h"
|
||||
#include "../../../lcd/dwin/creality/dwin.h"
|
||||
#elif ENABLED(SOVOL_SV06_RTS)
|
||||
#include "../../../lcd/sovol_rts/sovol_rts.h"
|
||||
#endif
|
||||
|
|
@ -759,7 +759,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
for (;;) {
|
||||
pos = planner.get_axis_position_mm(axis);
|
||||
if (inInc > 0 ? (pos >= cmp) : (pos <= cmp)) break;
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
}
|
||||
//if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(axis == Y_AXIS ? PSTR("Y=") : PSTR("X=", pos);
|
||||
|
||||
|
|
@ -803,7 +803,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
#endif
|
||||
|
||||
abl.reenable = false; // Don't re-enable after modifying the mesh
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
|
||||
} // inner
|
||||
} // outer
|
||||
|
|
|
|||
|
|
@ -61,7 +61,7 @@
|
|||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "../../lcd/e3v2/creality/dwin.h"
|
||||
#include "../../lcd/dwin/creality/dwin.h"
|
||||
#elif ENABLED(SOVOL_SV06_RTS)
|
||||
#include "../../lcd/sovol_rts/sovol_rts.h"
|
||||
#endif
|
||||
|
|
@ -129,15 +129,14 @@
|
|||
#if ENABLED(Z_SAFE_HOMING)
|
||||
|
||||
inline void home_z_safely() {
|
||||
|
||||
// Potentially disable Fixed-Time Motion for homing
|
||||
TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE());
|
||||
|
||||
DEBUG_SECTION(log_G28, "home_z_safely", DEBUGGING(LEVELING));
|
||||
|
||||
// Disallow Z homing if X or Y homing is needed
|
||||
if (homing_needed_error(_BV(X_AXIS) | _BV(Y_AXIS))) return;
|
||||
|
||||
// Potentially disable Fixed-Time Motion for homing
|
||||
TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE());
|
||||
|
||||
sync_plan_position();
|
||||
|
||||
/**
|
||||
|
|
|
|||
|
|
@ -96,7 +96,7 @@
|
|||
|
||||
void GcodeSuite::G76() {
|
||||
auto report_temps = [](millis_t &ntr, millis_t timeout=0) {
|
||||
idle_no_sleep();
|
||||
marlin.idle_no_sleep();
|
||||
const millis_t ms = millis();
|
||||
if (ELAPSED(ms, ntr)) {
|
||||
ntr = ms + 1000;
|
||||
|
|
|
|||
|
|
@ -28,8 +28,6 @@
|
|||
#include "../queue.h"
|
||||
#include "../../libs/hex_print.h"
|
||||
|
||||
#include "../../MarlinCore.h" // for idle()
|
||||
|
||||
/**
|
||||
* M100: Free Memory Watcher
|
||||
*
|
||||
|
|
@ -178,7 +176,7 @@ inline int32_t count_test_bytes(const char * const start_free_memory) {
|
|||
SERIAL_EOL();
|
||||
start_free_memory += 16;
|
||||
serial_delay(25);
|
||||
idle();
|
||||
marlin.idle();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -209,12 +207,12 @@ inline int check_for_free_memory_corruption(FSTR_P const title) {
|
|||
if (end_free_memory < start_free_memory) {
|
||||
SERIAL_ECHOPGM(" end_free_memory < Heap ");
|
||||
//SET_INPUT_PULLUP(63); // if the developer has a switch wired up to their controller board
|
||||
//safe_delay(5); // this code can be enabled to pause the display as soon as the
|
||||
//while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch
|
||||
// idle(); // being on pin-63 which is unassigend and available on most controller
|
||||
//safe_delay(20); // boards.
|
||||
//safe_delay(5); // this code can be enabled to pause the display as soon as the
|
||||
//while ( READ(63)) // malfunction is detected. It is currently defaulting to a switch
|
||||
// marlin.idle(); // being on pin-63 which is unassigend and available on most controller
|
||||
//safe_delay(20); // boards.
|
||||
//while ( !READ(63))
|
||||
// idle();
|
||||
// marlin.idle();
|
||||
serial_delay(20);
|
||||
#if ENABLED(M100_FREE_MEMORY_DUMPER)
|
||||
M100_dump_routine(F(" Memory corruption detected with end_free_memory<Heap\n"), (const char*)0x1B80, 0x0680);
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
#if ENABLED(PINS_DEBUGGING)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for pin_is_protected, wait_for_user
|
||||
#include "../../pins/pinsDebug.h"
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
|
|
@ -64,7 +63,7 @@ inline void toggle_pins() {
|
|||
for (uint8_t i = start; i <= end; ++i) {
|
||||
pin_t pin = GET_PIN_MAP_PIN_M43(i);
|
||||
if (!isValidPin(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) {
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) {
|
||||
printPinStateExt(pin, ignore_protection, true, F("Untouched "));
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
|
@ -328,7 +327,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; ++i) {
|
||||
pin_t pin = GET_PIN_MAP_PIN_M43(i);
|
||||
if (!isValidPin(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) continue;
|
||||
can_watch = true;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
delay(1);
|
||||
|
|
@ -358,7 +357,7 @@ void GcodeSuite::M43() {
|
|||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
wait_for_user = true;
|
||||
marlin.wait_start();
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.continue_prompt(F("M43 Waiting...")));
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
ExtUI::onUserConfirmRequired(F("M43 Waiting..."));
|
||||
|
|
@ -371,7 +370,7 @@ void GcodeSuite::M43() {
|
|||
for (uint8_t i = first_pin; i <= last_pin; ++i) {
|
||||
const pin_t pin = GET_PIN_MAP_PIN_M43(i);
|
||||
if (!isValidPin(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && marlin.pin_is_protected(pin))) continue;
|
||||
const byte val =
|
||||
/*
|
||||
isAnalogPin(pin)
|
||||
|
|
@ -387,7 +386,7 @@ void GcodeSuite::M43() {
|
|||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
ui.update();
|
||||
if (!wait_for_user) break;
|
||||
if (!marlin.wait_for_user) break;
|
||||
#endif
|
||||
|
||||
safe_delay(200);
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
#if ENABLED(CONFIGURABLE_MACHINE_NAME)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
/**
|
||||
|
|
@ -39,20 +38,20 @@ void GcodeSuite::M550() {
|
|||
bool did_set = true;
|
||||
|
||||
if (parser.seenval('P'))
|
||||
machine_name = parser.value_string();
|
||||
marlin.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;
|
||||
marlin.machine_name = parser.string_arg[0] == 'P' ? &parser.string_arg[1] : parser.string_arg;
|
||||
else if (parser.has_string())
|
||||
machine_name = parser.string_arg;
|
||||
marlin.machine_name = parser.string_arg;
|
||||
else
|
||||
did_set = false;
|
||||
|
||||
if (did_set) {
|
||||
machine_name.trim();
|
||||
marlin.machine_name.trim();
|
||||
ui.reset_status(false);
|
||||
}
|
||||
else
|
||||
SERIAL_ECHOLNPGM("RepRap name: ", &machine_name);
|
||||
SERIAL_ECHOLNPGM("RepRap name: ", &marlin.machine_name);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -21,26 +21,21 @@
|
|||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if DISABLED(EMERGENCY_PARSER)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for wait_for_heatup, kill, M112_KILL_STR
|
||||
#include "../../module/motion.h" // for quickstop_stepper
|
||||
|
||||
/**
|
||||
* M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature.
|
||||
*/
|
||||
void GcodeSuite::M108() {
|
||||
TERN_(HAS_RESUME_CONTINUE, wait_for_user = false);
|
||||
wait_for_heatup = false;
|
||||
marlin.end_waiting();
|
||||
}
|
||||
|
||||
/**
|
||||
* M112: Full Shutdown
|
||||
*/
|
||||
void GcodeSuite::M112() {
|
||||
kill(FPSTR(M112_KILL_STR), nullptr, true);
|
||||
marlin.kill(FPSTR(M112_KILL_STR), nullptr, true);
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
@ -52,5 +47,3 @@ void GcodeSuite::M112() {
|
|||
void GcodeSuite::M410() {
|
||||
quickstop_stepper();
|
||||
}
|
||||
|
||||
#endif // !EMERGENCY_PARSER
|
||||
|
|
|
|||
|
|
@ -25,7 +25,6 @@
|
|||
#if ENABLED(DIRECT_PIN_CONTROL)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for pin_is_protected and idle()
|
||||
#include "../../module/planner.h"
|
||||
|
||||
void protected_pin_err();
|
||||
|
|
@ -40,7 +39,7 @@ void GcodeSuite::M226() {
|
|||
const pin_t pin = GET_PIN_MAP_PIN(pin_number);
|
||||
|
||||
if (WITHIN(pin_state, -1, 1) && pin > -1) {
|
||||
if (pin_is_protected(pin))
|
||||
if (marlin.pin_is_protected(pin))
|
||||
protected_pin_err();
|
||||
else {
|
||||
int target = LOW;
|
||||
|
|
@ -51,7 +50,7 @@ void GcodeSuite::M226() {
|
|||
case 0: target = LOW; break;
|
||||
case -1: target = !extDigitalRead(pin); break;
|
||||
}
|
||||
while (int(extDigitalRead(pin)) != target) idle();
|
||||
while (int(extDigitalRead(pin)) != target) marlin.idle();
|
||||
}
|
||||
} // pin_state -1 0 1 && pin > -1
|
||||
} // parser.seen('P')
|
||||
|
|
|
|||
|
|
@ -37,8 +37,6 @@
|
|||
#define OUTPUT_OPEN_DRAIN OUTPUT_OPEN_DRAIN
|
||||
#endif
|
||||
|
||||
bool pin_is_protected(const pin_t pin);
|
||||
|
||||
void protected_pin_err() {
|
||||
SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN);
|
||||
}
|
||||
|
|
@ -63,7 +61,7 @@ void GcodeSuite::M42() {
|
|||
|
||||
const pin_t pin = GET_PIN_MAP_PIN(pin_index);
|
||||
|
||||
if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
|
||||
if (!parser.boolval('I') && marlin.pin_is_protected(pin)) return protected_pin_err();
|
||||
|
||||
bool avoidWrite = false;
|
||||
if (parser.seenval('T')) {
|
||||
|
|
|
|||
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue