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

This commit is contained in:
Scott Lahteine 2025-12-21 17:41:10 -06:00
commit a4a38dfda3
433 changed files with 5968 additions and 5704 deletions

View file

@ -121,7 +121,7 @@ Unsure where to begin contributing to Marlin? You can start by looking through t
### Pull Requests
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and GitHub's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
* Fill in [the required template](pull_request_template.md).
* Don't include issue numbers in the PR title.

View file

@ -61,7 +61,7 @@
// @section info
// Author info of this build printed to the host during boot and M115
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Original author or contributor.
#define STRING_CONFIG_H_AUTHOR "(MarlinFirmware)" // Original author or contributor.
//#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes)
// @section machine
@ -468,7 +468,7 @@
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
// @section temperature
// @section temperature sensors
/**
* Temperature Sensors:
@ -500,7 +500,7 @@
* 10 : 100 RS PRO 198-961
* 11 : 100 Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1%
* 12 : 100 Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed
* 13 : 100 Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1%
* 13 : 100 Hisense up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1%
* 14 : 100 (R25), 4092K (beta25), 4.7 pull-up, bed thermistor as used in Ender-5 S1
* 15 : 100 Calibrated for JGAurora A5 hotend
* 17 : 100 Dagoma NTC white thermistor
@ -652,6 +652,8 @@
#define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort.
#endif
// @section temperature
// Below this temperature the heater will be switched off
// because it probably indicates a broken thermistor wire.
#define HEATER_0_MINTEMP 5
@ -718,13 +720,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
@ -822,9 +824,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
@ -905,9 +907,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.
@ -1661,7 +1663,7 @@
* Nozzle-to-Probe offsets { X, Y, Z }
*
* X and Y offset
* Use a caliper or ruler to measure the distance from the tip of
* Use a caliper or ruler to measure the distance (in mm) from the tip of
* the Nozzle to the center-point of the Probe in the X and Y axes.
*
* Z offset
@ -1697,7 +1699,7 @@
* | [-] |
* O-- FRONT --+
*/
#define NOZZLE_TO_PROBE_OFFSET { 10, 10, 0 }
#define NOZZLE_TO_PROBE_OFFSET { 10, 10, 0 } // (mm) X, Y, Z distance from Nozzle tip to Probe trigger-point
// Enable and set to use a specific tool for probing. Disable to allow any tool.
#define PROBING_TOOL 0
@ -1860,15 +1862,12 @@
//#define DISABLE_V
//#define DISABLE_W
// Turn off the display blinking that warns about possible accuracy reduction
//#define DISABLE_REDUCED_ACCURACY_WARNING
// @section extruder
//#define DISABLE_E // Disable the extruder when not stepping
#define DISABLE_OTHER_EXTRUDERS // Keep only the active extruder enabled
// @section motion
// @section stepper drivers
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
#define INVERT_X_DIR false
@ -1881,8 +1880,6 @@
//#define INVERT_V_DIR false
//#define INVERT_W_DIR false
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
#define INVERT_E0_DIR false
#define INVERT_E1_DIR false
@ -2527,7 +2524,7 @@
//
//#define TEMPERATURE_UNITS_SUPPORT
// @section temperature
// @section temperature presets
//
// Preheat Constants - Up to 10 are supported without changes

View file

@ -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
@ -1150,9 +1160,26 @@
#if ENABLED(FT_MOTION)
//#define FTM_IS_DEFAULT_MOTION // Use FT Motion as the factory default?
//#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 NO_STANDARD_MOTION // Disable the standard motion system entirely to save Flash and RAM
#if DISABLED(NO_STANDARD_MOTION)
//#define FTM_HOME_AND_PROBE // Use FT Motion for homing / probing. Disable if FT Motion breaks these functions.
#endif
//#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
// Disable unused shapers if you need more free space
#define FTM_SHAPER_ZV
#define FTM_SHAPER_ZVD
#define FTM_SHAPER_ZVDD
#define FTM_SHAPER_ZVDDD
#define FTM_SHAPER_EI
#define FTM_SHAPER_2HEI
#define FTM_SHAPER_3HEI
#define FTM_SHAPER_MZV
#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 +1218,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 +1236,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
@ -1497,6 +1526,9 @@
// @section lcd
// Turn off the display blinking that warns about possible accuracy reduction
//#define DISABLE_REDUCED_ACCURACY_WARNING
#if HAS_MANUAL_MOVE_MENU
#define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel
#define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines
@ -1784,6 +1816,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 +1835,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.
@ -1848,17 +1890,21 @@
// SD Card Sorting options
#if ENABLED(SDCARD_SORT_ALPHA)
#define SDSORT_REVERSE false // Default to sorting file names in reverse order.
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
#define SDSORT_FOLDERS -1 // -1=above 0=none 1=below
#define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1>
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#define SDSORT_QUICK true // Use Quick Sort as a sorting algorithm. Otherwise use Bubble Sort.
#define SDSORT_QUICK true // Use Quick Sort as a sorting algorithm. Otherwise use Bubble Sort.
#define SDSORT_REVERSE false // Default to sorting file names in reverse order.
#define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). Costs 27 bytes each.
#define SDSORT_FOLDERS -1 // -1=above 0=none 1=below
#define SDSORT_GCODE false // Enable G-code M34 to set sorting behaviors: M34 S<-1|0|1> F<-1|0|1>
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
#define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting.
#if ENABLED(SDSORT_USES_RAM)
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
#if ENABLED(SDSORT_CACHE_NAMES)
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
#endif
#endif
// Allow international symbols in long filenames. To display correctly, the
@ -2312,7 +2358,7 @@
//#define WATCHDOG_RESET_MANUAL
#endif
// @section lcd
// @section baby-stepping
/**
* Babystepping enables movement of the axes by tiny increments without changing
@ -2565,13 +2611,15 @@
#endif
#endif // PTC_PROBE || PTC_BED || PTC_HOTEND
// @section extras
// @section gcode
//
// G60/G61 Position Save and Return
//
//#define SAVED_POSITIONS 1 // Each saved position slot costs 12 bytes
// @section motion
//
// G2/G3 Arc Support
//
@ -2603,6 +2651,8 @@
*/
//#define DIRECT_STEPPING
// @section calibrate
/**
* G38 Probe Target
*
@ -2809,7 +2859,7 @@
*/
//#define EXTRA_FAN_SPEED
// @section gcode
// @section firmware retraction
/**
* Firmware-based and LCD-controlled retract
@ -3626,7 +3676,7 @@
//#define PHOTO_RETRACT_MM 6.5 // (mm) E retract/recover for the photo move (M240 R S)
// Canon RC-1 or homebrew digital camera trigger
// Data from: https://www.doc-diy.net/photo/rc-1_hacked/
// Data from: https://web.archive.org/web/20250327153953/www.doc-diy.net/photo/rc-1_hacked/
//#define PHOTOGRAPH_PIN 23
// Canon Hack Development Kit
@ -4197,7 +4247,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
@ -4263,7 +4313,7 @@
* Developed by Chris Barr at Aus3D.
*
* Wiki: https://wiki.aus3d.com.au/Magnetic_Encoder
* Github: https://github.com/Aus3D/MagneticEncoder
* GitHub: https://github.com/Aus3D/MagneticEncoder
*
* Supplier: https://aus3d.com.au/products/magnetic-encoder-module
* Alternative Supplier: https://reliabuild3d.com/

View file

@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
//#define STRING_DISTRIBUTION_DATE "2025-11-26"
//#define STRING_DISTRIBUTION_DATE "2025-12-21"
/**
* The protocol for communication to the host. Protocol indicates communication
@ -58,7 +58,7 @@
/**
* The SOURCE_CODE_URL is the location where users will find the Marlin Source
* Code which is installed on the device. In most cases unless the manufacturer
* has a distinct Github fork the Source Code URL should just be the main
* has a distinct GitHub fork the Source Code URL should just be the main
* Marlin repository.
*/
//#define SOURCE_CODE_URL "github.com/MarlinFirmware/Marlin"

View file

@ -96,7 +96,7 @@ void MarlinHAL::init() {
// Might disable other peripherals using the pin; to circumvent that please undefine one of the above things!
// The true culprit is the AVR ArduinoCore that enables peripherals redundantly.
// (USART1 on the GeeeTech GT2560)
// https://www.youtube.com/watch?v=jMgCvRXkexk
// https://youtube.be/jMgCvRXkexk
_ATmega_savePinAlternate(BEEPER_PIN);
OUT_WRITE(BEEPER_PIN, LOW);
@ -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

View file

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

View file

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

View file

@ -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,14 @@ 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) // (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_PRESCALE STEPPER_TIMER_PRESCALE
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)

View file

@ -27,7 +27,6 @@
#ifdef ARDUINO_ARCH_SAM
#include "../../inc/MarlinConfig.h"
#include "../../MarlinCore.h"
#include <Wire.h>
#include "usb/usb_task.h"

View file

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

View file

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

View file

@ -24,7 +24,7 @@
/**
* Description: Tone function for Arduino Due and compatible (SAM3X8E)
* Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
* Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13
*/
#ifdef ARDUINO_ARCH_SAM

View file

@ -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,18 @@ 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_RATE STEPPER_TIMER_RATE // (Hz) 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)

View file

@ -0,0 +1,5 @@
# editorconfig.org
[{*.c,*.cpp,*.h}]
indent_style = tab
indent_size = 4

View file

@ -271,7 +271,7 @@ void MarlinHAL::adc_start(const pin_t pin) {
uint32_t mv;
esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
adc_result = mv * isr_float_t(1023) / isr_float_t(ADC_REFERENCE_VOLTAGE) / isr_float_t(1000);
adc_result = (mv * 1023) * (1000.f / (ADC_REFERENCE_VOLTAGE));
// Change the attenuation level based on the new reading
adc_atten_t atten;

View file

@ -76,7 +76,6 @@
// Types
// ------------------------
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef int16_t pin_t;
typedef struct pwm_pin {
@ -194,7 +193,7 @@ public:
static void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
// Tasks, called from marlin.idle()
static void idletask();
// Reset

View file

@ -24,7 +24,7 @@
/**
* Description: Tone function for ESP32
* Derived from https://forum.arduino.cc/index.php?topic=136500.msg2903012#msg2903012
* Derived from https://forum.arduino.cc/t/arduino-due-and-tone/133302/13
*/
#ifdef ARDUINO_ARCH_ESP32

View file

@ -156,38 +156,43 @@ void stepperTask(void *parameter) {
while (dma.rw_pos < DMA_SAMPLE_COUNT) {
#if ENABLED(FT_MOTION)
if (using_ftMotion) {
if (using_ftMotion) {
#if ENABLED(FT_MOTION)
if (!nextMainISR) stepper.ftMotion_stepper();
nextMainISR = 0;
}
#endif
#endif
}
else {
if (!using_ftMotion) {
if (!nextMainISR) {
stepper.pulse_phase_isr();
nextMainISR = stepper.block_phase_isr();
}
#if ENABLED(LIN_ADVANCE)
else if (!nextAdvanceISR) {
stepper.advance_isr();
nextAdvanceISR = stepper.la_interval;
#if HAS_STANDARD_MOTION
if (!nextMainISR) {
stepper.pulse_phase_isr();
nextMainISR = stepper.block_phase_isr();
}
#endif
else
i2s_push_sample();
#if ENABLED(LIN_ADVANCE)
else if (!nextAdvanceISR) {
stepper.advance_isr();
nextAdvanceISR = stepper.la_interval;
}
#endif
else
i2s_push_sample();
nextMainISR--;
nextMainISR--;
#if ENABLED(LIN_ADVANCE)
if (nextAdvanceISR == stepper.LA_ADV_NEVER)
nextAdvanceISR = stepper.la_interval;
#if ENABLED(LIN_ADVANCE)
if (nextAdvanceISR == stepper.LA_ADV_NEVER)
nextAdvanceISR = stepper.la_interval;
if (nextAdvanceISR && nextAdvanceISR != stepper.LA_ADV_NEVER)
nextAdvanceISR--;
#endif
#endif // HAS_STANDARD_MOTION
if (nextAdvanceISR && nextAdvanceISR != stepper.LA_ADV_NEVER)
nextAdvanceISR--;
#endif
}
}
}

View file

@ -30,41 +30,45 @@
#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_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 +78,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)

View file

@ -57,7 +57,6 @@
#define __bss_end __bss_end__
// Types
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef uint8_t pin_t; // Parity with mfl platform
// Servo

View file

@ -69,10 +69,6 @@
#endif
#endif
#ifndef HAL_TIMER_RATE
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
#ifndef STEP_TIMER
#define STEP_TIMER MF_TIMER_STEP
#endif
@ -121,9 +117,10 @@ void HAL_timer_start(const uint8_t timer_number, const uint32_t frequency) {
if (is_step) {
timer.setPrescaler(STEPPER_TIMER_PRESCALE);
timer.setRolloverValue(_MIN(static_cast<hal_timer_t>(HAL_TIMER_TYPE_MAX),
(HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)),
TimerFormat::TICK);
timer.setRolloverValue(
_MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE))),
TimerFormat::TICK
);
is_step_timer_initialized = true;
}
else {

View file

@ -29,26 +29,30 @@
// 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();
#ifndef HAL_TIMER_RATE
extern uint32_t GetStepperTimerClkFreq();
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
// 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 STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) // Prescaler = 30
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs
// Pulse Timer (counter) calculations
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
// Timer interrupt priorities
#define STEP_TIMER_IRQ_PRIORITY 2

View file

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

View file

@ -53,7 +53,7 @@ Just searching for `SCB->VTOR` should yield some results. From there, you just n
> Some vendors publish incomplete source code. But they sometimes leave version control related files in the repo, which can contain previous version of files that were removed. Find these by including folders like `.git` or `.svn` in your search.
> [!NOTE]
> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo.
> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/main/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo.
2. Using a linker script

View file

@ -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,13 +65,13 @@ 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
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define MF_TIMER_PULSE MF_TIMER_STEP
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
//
// HAL functions
@ -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);
//

View file

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

View file

@ -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,20 @@ 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_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

View file

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

View file

@ -49,6 +49,8 @@
#include <Servo.h>
#include "../../MarlinCore.h"
class libServo: public Servo {
public:
void move(const int value) {

View file

@ -22,7 +22,7 @@
/**
* digipot_mcp4451_I2C_routines.c
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
* Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef TARGET_LPC1768

View file

@ -23,7 +23,7 @@
/**
* digipot_mcp4451_I2C_routines.h
* Adapted from https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
* Adapted from https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
*/
#ifdef __cplusplus

View file

@ -57,9 +57,9 @@
#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) // frequency of timers peripherals
#define HAL_TIMER_RATE ((F_CPU) / 4) // (Hz) Frequency of timers peripherals
#ifndef MF_TIMER_STEP
#define MF_TIMER_STEP 0 // Timer Index for Stepper
@ -74,22 +74,21 @@ typedef uint32_t hal_timer_t;
#define MF_TIMER_PWM 3 // Timer Index for PWM
#endif
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define TEMP_TIMER_RATE 1000000 // 1MHz
#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 (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_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

View file

@ -21,7 +21,7 @@
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef TARGET_LPC1768

View file

@ -41,8 +41,8 @@ if pioutil.is_pio_build():
from ctypes import windll
from pathlib import PureWindowsPath
# getting list of drives
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-drive-letters-in-python
# Getting a list of drives
# https://stackoverflow.com/questions/827371/is-there-a-way-to-list-all-the-available-windows-drives
drives = []
bitmask = windll.kernel32.GetLogicalDrives()
for letter in string.ascii_uppercase:

View file

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

View file

@ -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,21 @@ 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_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) / 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_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

View file

@ -21,7 +21,7 @@
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef __PLAT_NATIVE_SIM__

View file

@ -28,21 +28,116 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
#include "../../module/temperature.h" // For OVERSAMPLENR
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
// ------------------------
// 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] = {4095, 4095, 4095, 4095, 4095}; // Averaged ADC values (single reading equivalent) - initialized to max (open circuit)
// Core monitoring for watchdog
volatile uint32_t core0_last_heartbeat = 0; // Timestamp of Core 0's last activity
volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity
#if ENABLED(MARLIN_DEV_MODE)
volatile bool core1_freeze_test = false; // Flag to freeze Core 1 for watchdog testing
#endif
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
// Core 1 ADC reading task - dynamically reads all enabled channels with oversampling
void core1_adc_task() {
static uint32_t last_temp_update = 0;
while (true) {
#if ENABLED(MARLIN_DEV_MODE)
// Check if we should freeze for watchdog test
if (core1_freeze_test) {
// Stop updating heartbeat and spin forever
while (core1_freeze_test) {
busy_wait_us(100000); // 100ms delay
}
}
#endif
// 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]++;
// When we reach the full oversampling count, calculate averaged value (Marlin ISR does its own oversampling)
if (adc_counts[channel] >= OVERSAMPLENR) {
adc_values[channel] = adc_accumulators[channel] / OVERSAMPLENR; // Return single-reading equivalent
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 just provides ADC readings - don't trigger temperature updates from here
// Let Marlin's main temperature ISR on Core 0 handle the timing and updates
uint32_t now = time_us_32();
if (now - last_temp_update >= 100000) { // 100ms = 100000 microseconds
last_temp_update = now;
#if ENABLED(USE_WATCHDOG)
// Refresh watchdog here like AVR ISR does indirectly via temperature updates
// Use 2 second delay to allow watchdog_init to be called during boot
static uint32_t core1_start_time = 0;
if (core1_start_time == 0) core1_start_time = time_us_32();
if (time_us_32() - core1_start_time > 2000000) {
hal.watchdog_refresh(1); // Refresh from Core 1
}
#endif
}
// Delay between full scan cycles
busy_wait_us(10000); // 10ms between scans
}
}
volatile uint16_t adc_result;
// ------------------------
@ -113,73 +208,91 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); }
void MarlinHAL::watchdog_init() {
#if DISABLED(DISABLE_WATCHDOG_INIT)
static_assert(WDT_TIMEOUT_US > 1000, "WDT Timeout is too small, aborting");
// Initialize Core 0 heartbeat
core0_last_heartbeat = time_us_32();
watchdog_enable(WDT_TIMEOUT_US/1000, true);
#endif
}
void MarlinHAL::watchdog_refresh() {
watchdog_update();
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // heartbeat indicator
#endif
void MarlinHAL::watchdog_refresh(const uint8_t core/*=0*/) {
if (core == 0) {
// Update Core 0 heartbeat
core0_last_heartbeat = time_us_32();
// Check if Core 1 is alive (2 second timeout)
if (time_us_32() - core1_last_heartbeat < 2000000) {
watchdog_update(); // Only refresh if Core 1 is responding
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Heartbeat indicator
#endif
}
// If Core 1 is stuck, don't refresh - let watchdog reset the system
}
else {
// Update Core 1 heartbeat
core1_last_heartbeat = time_us_32();
// Check if Core 0 is alive (2 second timeout)
if (time_us_32() - core0_last_heartbeat < 2000000) {
watchdog_update(); // Only refresh if Core 0 is responding
#if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
TOGGLE(LED_PIN); // Heartbeat indicator
#endif
}
// If Core 0 is stuck, don't refresh - let watchdog reset the system
}
}
#endif
#endif // USE_WATCHDOG
// ------------------------
// 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(); }
extern "C" {
void * _sbrk(int incr);
extern unsigned int __bss_end__; // end of bss section
extern unsigned int __StackLimit; // Lowest address the stack can grow to
}
// Return free memory between end of heap (or end bss) and whatever is current
// Return free memory between end of heap and start of stack
int freeMemory() {
int free_memory, heap_end = (int)_sbrk(0);
return (int)&free_memory - (heap_end ?: (int)&__bss_end__);
void* heap_end = _sbrk(0);
// Use the linker-provided stack limit instead of a local variable
// __StackLimit is the lowest address the stack can grow to
return (char*)&__StackLimit - (char*)heap_end;
}
#endif // __PLAT_RP2040__

View file

@ -40,12 +40,39 @@
#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
//
#include "MarlinSerial.h"
#if !WITHIN(SERIAL_PORT, -1, 1)
#error "SERIAL_PORT must be from -1 to 1."
#endif
#ifdef SERIAL_PORT_2
#if !WITHIN(SERIAL_PORT_2, -1, 1)
#error "SERIAL_PORT_2 must be from -1 to 1."
#endif
#endif
#ifdef SERIAL_PORT_3
#if !WITHIN(SERIAL_PORT_3, -1, 1)
#error "SERIAL_PORT_3 must be from -1 to 1."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if !WITHIN(LCD_SERIAL_PORT, -1, 1)
#error "LCD_SERIAL_PORT must be from -1 to 1."
#endif
#endif
// ------------------------
// Defines
// ------------------------
@ -85,8 +112,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
@ -128,7 +153,7 @@ public:
// Watchdog
static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
static void watchdog_refresh(const uint8_t=0) IF_DISABLED(USE_WATCHDOG, {});
static void init(); // Called early in setup()
static void init_board() {} // Called less early in setup()
@ -141,7 +166,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 +189,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; }

View file

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

View file

@ -30,10 +30,40 @@
#include "../../feature/e_parser.h"
#endif
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X)
#if WITHIN(SERIAL_PORT, 0, 3)
IMPLEMENT_SERIAL(SERIAL_PORT);
#include <HardwareSerial.h>
// Marlin uses: -1=USB, 0=UART0, 1=UART1
// Arduino uses: Serial=USB, Serial1=UART0, Serial2=UART1
//
// To remap Arduino's numbering to Marlin's convention, we create MarlinSerial0/MarlinSerial1
// as new UART instances with custom pins.
//
// We use distinct names (MarlinSerial0/MarlinSerial1) to avoid symbol conflicts with
// the Arduino framework's pre-defined Serial1/Serial2 objects, which use the same
// underlying hardware (_UART0_ and _UART1_).
// Create Serial0 as UART0 with custom or default pins
arduino::UART MarlinSerial0(
#if PINS_EXIST(SERIAL0_TX, SERIAL0_RX)
SERIAL0_TX_PIN, SERIAL0_RX_PIN // Custom pins for UART0 (Marlin Serial0)
#else
0, 1 // Default UART0 pins (GP0/GP1)
#endif
);
// Not using PINS_EXIST(SERIAL1_TX, SERIAL1_RX) because SERIAL1_TX and SERIAL1_RX
// are defined in framework-arduino-mbed/variants/RASPBERRY_PI_PICO/pins_arduino.h
// Create Serial1 as UART1 with custom or default pins
#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN)
arduino::UART MarlinSerial1(SERIAL1_TX_PIN, SERIAL1_RX_PIN); // Custom pins for UART1 (Marlin Serial1)
#endif
// Wrap the serial ports for Marlin
DefaultSerial0 MSerial0(false, MarlinSerial0); // Marlin Serial0 = UART0
#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN)
DefaultSerial1 MSerial1(false, MarlinSerial1); // Marlin Serial1 = UART1
#endif
DefaultSerial2 MSerial2(false, Serial); // Marlin Serial2 = USB (-1)
#endif // __PLAT_RP2040__

View file

@ -29,20 +29,50 @@
#include "../../core/serial_hook.h"
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
extern DefaultSerial1 MSerial0;
/**
* Serial Port Configuration for RP2040 (Raspberry Pi Pico)
*
* Arduino-Pico Core Serial Objects:
* - Serial: USB Serial (CDC ACM)
* - Serial1: Hardware UART0
* - Serial2: Hardware UART1
* - SerialUSB: Alias for Serial (USB)
*
* Marlin Serial Wrappers:
* - MSerial0: Wrapper for MarlinSerial0 (UART0), used as Serial0
* - MSerial1: Wrapper for MarlinSerial1 (UART1), declared dynamically if used
* - MSerial2: Wrapper for Serial (USB)
* - USBSerial: Wrapper for SerialUSB (USB)
*
* How it all joins together:
* - Configuration defines SERIAL_PORT, SERIAL_PORT_2, etc. (-1 to 1 range)
* - shared/serial_ports.h maps these to MYSERIAL1, MYSERIAL2, etc.
* - MYSERIAL1 uses MSerialX based on the port index
* - USB ports (-1) use USB_SERIAL_PORT (MSerial2)
*/
// Forward declare our custom Serial objects (defined in MarlinSerial.cpp)
namespace arduino { class UART; }
extern arduino::UART MarlinSerial0; // Always declared
extern arduino::UART MarlinSerial1; // Custom Marlin Serial1 to avoid conflict
typedef ForwardSerial1Class< decltype(MarlinSerial0) > DefaultSerial0;
extern DefaultSerial0 MSerial0;
typedef ForwardSerial1Class< decltype(MarlinSerial1) > DefaultSerial1;
extern DefaultSerial1 MSerial1;
typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial2;
extern DefaultSerial2 MSerial2;
typedef ForwardSerial1Class<decltype(SerialUSB)> USBSerialType;
extern USBSerialType USBSerial;
#define Serial0 Serial
#define _DECLARE_SERIAL(X) \
typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
typedef ForwardSerial1Class<decltype(MarlinSerial##X)> DefaultSerial##X; \
extern DefaultSerial##X MSerial##X
#define DECLARE_SERIAL(X) _DECLARE_SERIAL(X)
#define SERIAL_INDEX_MIN 0
#define SERIAL_INDEX_MAX 6
#define USB_SERIAL_PORT(...) MSerial0
#define SERIAL_INDEX_MAX 1
#define USB_SERIAL_PORT(...) MSerial2
#include "../shared/serial_ports.h"
#if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI)

View file

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

View file

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

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

View file

@ -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,20 @@ 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_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

View file

@ -1,6 +1,6 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2024 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
@ -22,9 +22,7 @@
#pragma once
/**
* strlen_cx.h
* RP2040 LCD-specific defines
*/
constexpr inline int strlen_constexpr(const char *str) {
return *str ? 1 + strlen_constexpr(str + 1) : 0;
}
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

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

View file

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

View file

@ -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,14 @@ 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_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 +142,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;

View file

@ -25,7 +25,7 @@
* Based on SAMD51 HAL by Giuliano Zaro (AKA GMagician)
*/
// adapted from I2C/master/master.c example
// https://www-users.cs.york.ac.uk/~pcc/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
// https://www-users.york.ac.uk/~pcc1/MCP/HAPR-Course-web/CMSIS/examples/html/master_8c_source.html
#ifdef __SAMD21__

View file

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

View file

@ -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,14 @@ 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_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)

View file

@ -63,8 +63,6 @@
// Types
// ------------------------
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef int32_t pin_t; // Parity with platform/ststm32
class libServo;
@ -157,7 +155,7 @@ public:
static void delay_ms(const int ms) { delay(ms); }
// Tasks, called from idle()
// Tasks, called from marlin.idle()
static void idletask();
// Reset

View file

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

View file

@ -81,10 +81,6 @@
#define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
#endif
#ifndef HAL_TIMER_RATE
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
#ifndef STEP_TIMER
#define STEP_TIMER MCU_STEP_TIMER
#endif
@ -141,7 +137,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
*/
timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
timer_instance[timer_num]->setOverflow(_MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* / frequency */)), TICK_FORMAT);
break;
case MF_TIMER_TEMP: // TEMP TIMER - any available 16bit timer
timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);

View file

@ -38,7 +38,7 @@
// of adding a run-time check and HAL_TIMER_TYPE_MAX is refactored to allow unique
// values for each timer.
#define hal_timer_t uint32_t
#define HAL_TIMER_TYPE_MAX UINT16_MAX
#define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX)
// Marlin timer_instance[] content (unrelated to timer selection)
#define MF_TIMER_STEP 0 // Timer Index for Stepper
@ -48,23 +48,28 @@
#define TIMER_INDEX_(T) TIMER##T##_INDEX // TIMER#_INDEX enums (timer_index_t) depend on TIM#_BASE defines.
#define TIMER_INDEX(T) TIMER_INDEX_(T) // Convert Timer ID to HardwareTimer_Handle index.
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz
#ifndef HAL_TIMER_RATE
extern uint32_t GetStepperTimerClkFreq();
#define HAL_TIMER_RATE GetStepperTimerClkFreq()
#endif
// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
#define STEPPER_TIMER_RATE 2000000 // 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
// Timer configuration constants
#define STEPPER_TIMER_RATE 2000000
#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() should run at ~1kHz
#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
// Timer prescaler calculations
#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE))
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (ticks/μs) Stepper Timer ticks per µs
#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)
// Pulse Timer (counter) calculations
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
extern void Step_Handler();

View file

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

View file

@ -29,8 +29,6 @@ uint8_t ServoCount = 0;
#include "Servo.h"
//#include "Servo.h"
#include <boards.h>
#include <io.h>
#include <pwm.h>

View file

@ -84,7 +84,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((STEPPER_TIMER_RATE) / frequency)));
timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
HAL_timer_set_interrupt_priority(MF_TIMER_STEP, STEP_TIMER_IRQ_PRIO);
@ -97,7 +97,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
timer_set_count(TEMP_TIMER_DEV, 0);
timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(HAL_TIMER_TYPE_MAX, hal_timer_t((F_CPU) / (TEMP_TIMER_PRESCALE) / frequency)));
timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
HAL_timer_set_interrupt_priority(MF_TIMER_TEMP, TEMP_TIMER_IRQ_PRIO);
timer_generate_update(TEMP_TIMER_DEV);

View file

@ -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,26 @@ 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_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
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))

View file

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

View file

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

View file

@ -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,18 @@ 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) // (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_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

View file

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

View file

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

View file

@ -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,18 @@ 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) // (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_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

View file

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

View file

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

View file

@ -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)
@ -57,20 +57,19 @@ typedef uint32_t hal_timer_t;
#define TEMP_TIMER_RATE 1000000
#define TEMP_TIMER_FREQUENCY 1000
#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_PRESCALE (GPT_TIMER_RATE / STEPPER_TIMER_RATE)
#define HAL_TIMER_RATE GPT1_TIMER_RATE
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
#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_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

View file

@ -85,7 +85,7 @@
}
else {
// Enable DWT counter
// From https://stackoverflow.com/a/41188674/1469714
// From https://stackoverflow.com/questions/36378280/stm32-how-to-enable-dwt-cycle-counter/41188674#41188674
HW_REG(_DEM_CR) = HW_REG(_DEM_CR) | 0x01000000; // Enable trace
#if __CORTEX_M == 7
HW_REG(_LAR) = 0xC5ACCE55; // Unlock access to DWT registers, see https://developer.arm.com/documentation/ihi0029/e/ section B2.3.10

View file

@ -66,7 +66,7 @@ void * hook_get_usagefault_vector_address(unsigned vtor) { return (void*)(vtor +
void * hook_get_reserved_vector_address(unsigned vtor) { return (void*)(vtor + 0x07); }
// Common exception frame for ARM, should work for all ARM CPU
// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-fault-debug
// Described here (modified for convenience): https://interrupt.memfault.com/blog/cortex-m-hardfault-debug
struct __attribute__((packed)) ContextStateFrame {
uint32_t r0;
uint32_t r1;

View file

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

View file

@ -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[];

View file

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

View file

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

View file

@ -209,7 +209,10 @@
// "Ternary" that emits or omits the given content
#define EMIT(V...) V
#define OMIT(...)
#define TERN_(O,A) _TERN(_ENA_1(O),OMIT,EMIT)(A) // OPTION ? 'A' : '<nul>'
#define TERN_(O,A) TERF(O,EMIT)(A) // OPTION ? 'A' : '<nul>' ; Usage: TERN_(OPTION, EMITTHIS)
// Call G(...) or swallow with OMIT(...)
#define TERF(O,G) _TERN(_ENA_1(O),OMIT,G) // OPTION ? 'G' : 'OMIT' ; Usage: TERF(OPTION, CALLTHIS)(ARGS...)
// Macros to conditionally emit array items and function arguments
#define _OPTITEM(A...) A,

View file

@ -158,16 +158,16 @@ public:
MString& append_P(PGM_P const s) { int sz = length(); if (sz < SIZE) strlcpy_P(str + sz, s, SIZE - sz + 1); debug(F("pstring")); return *this; }
MString& append(FSTR_P const f) { return append_P(FTOP(f)); }
MString& append(const bool &b) { return append(b ? F("true") : F("false")); }
MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } return *this; }
MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } debug(F("char")); return *this; }
#if ENABLED(FASTER_APPEND)
MString& append(const int8_t &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); return *this; }
MString& append(const long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%ld", l); return *this; }
MString& append(const unsigned char &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); return *this; }
MString& append(const unsigned long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%lu", l); return *this; }
MString& append(const int8_t &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int8_t")); return *this; }
MString& append(const short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("short")); return *this; }
MString& append(const int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%d", i); debug(F("int")); return *this; }
MString& append(const long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%ld", l); debug(F("long")); return *this; }
MString& append(const unsigned char &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uchar")); return *this; }
MString& append(const unsigned short &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("ushort")); return *this; }
MString& append(const unsigned int &i) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%u", i); debug(F("uint")); return *this; }
MString& append(const unsigned long &l) { int sz = length(); SNPRINTF(&str[sz], SIZE - sz, "%lu", l); debug(F("ulong")); return *this; }
#else
MString& append(const int8_t &i) { char buf[ 5]; sprintf(buf, "%d", i); return append(buf); }
MString& append(const short &i) { char buf[12]; sprintf(buf, "%d", i); return append(buf); }

View file

@ -50,6 +50,7 @@ template <class L, class R> struct IF<true, L, R> { typedef L type; };
#define NUM_AXIS_DECL_LC(T,V) NUM_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V, T u=V, T v=V, T w=V)
#define MAIN_AXIS_NAMES NUM_AXIS_LIST(X, Y, Z, I, J, K, U, V, W)
#define MAIN_AXIS_NAMES_LC NUM_AXIS_LIST(x, y, z, i, j, k, u, v, w)
#define NUM_AXIS_CALL(G) do { NUM_AXIS_CODE(G(X_AXIS), G(Y_AXIS), G(Z_AXIS), G(I_AXIS), G(J_AXIS), G(K_AXIS), G(U_AXIS), G(V_AXIS), G(W_AXIS)); } while(0)
#define STR_AXES_MAIN NUM_AXIS_GANG("X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)
#define LOGICAL_AXIS_GANG(N,V...) NUM_AXIS_GANG(V) GANG_ITEM_E(N)
@ -68,6 +69,7 @@ template <class L, class R> struct IF<true, L, R> { typedef L type; };
#define LOGICAL_AXIS_NAMES_LC LOGICAL_AXIS_LIST(e, x, y, z, i, j, k, u, v, w)
#define LOGICAL_AXIS_MAP(F) MAP(F, LOGICAL_AXIS_NAMES)
#define LOGICAL_AXIS_MAP_LC(F) MAP(F, LOGICAL_AXIS_NAMES_LC)
#define LOGICAL_AXIS_CALL(G) do { LOGICAL_AXIS_CODE(G(E_AXIS), G(X_AXIS), G(Y_AXIS), G(Z_AXIS), G(I_AXIS), G(J_AXIS), G(K_AXIS), G(U_AXIS), G(V_AXIS), G(W_AXIS)); } while(0)
#define STR_AXES_LOGICAL LOGICAL_AXIS_GANG("E", "X", "Y", "Z", STR_I, STR_J, STR_K, STR_U, STR_V, STR_W)
#define NUM_AXIS_PAIRED_LIST(V...) LIST_N(DOUBLE(NUM_AXES), V)
@ -175,6 +177,7 @@ template <class L, class R> struct IF<true, L, R> { typedef L type; };
#define CARTES_CODE(x,y,z,e) XYZ_CODE(x,y,z) CODE_ITEM_E(e)
#define CARTES_GANG(x,y,z,e) XYZ_GANG(x,y,z) GANG_ITEM_E(e)
#define CARTES_AXIS_NAMES CARTES_LIST(X,Y,Z,E)
#define CARTES_AXIS_NAMES_LC CARTES_LIST(x,y,z,e)
#define CARTES_MAP(F) MAP(F, CARTES_AXIS_NAMES)
#if CARTES_COUNT
#define CARTES_COMMA ,
@ -554,7 +557,7 @@ struct XYval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)sqrtf(x*x + y*y); }
FI constexpr T magnitude() const { return (T)SQRT(x*x + y*y); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true
@ -731,7 +734,7 @@ struct XYZval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, sqrtf(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); }
FI constexpr T magnitude() const { return (T)TERN(HAS_X_AXIS, SQRT(NUM_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)), 0); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true
@ -816,6 +819,7 @@ 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 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 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; }
@ -901,7 +905,7 @@ struct XYZEval {
#endif
// Length reduced to one dimension
FI constexpr T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
FI constexpr T magnitude() const { return (T)SQRT(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k, + u*u, + v*v, + w*w)); }
// Pointer to the data as a simple array
explicit FI operator T* () { return pos; }
// If any element is true then it's true
@ -986,7 +990,10 @@ struct XYZEval {
FI XYZEval<T>& operator-=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k, u -= rs.u, v -= rs.v, w -= rs.w); return *this; }
FI XYZEval<T>& operator*=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k, u *= rs.u, v *= rs.v, w *= rs.w); return *this; }
FI XYZEval<T>& operator/=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k, u /= rs.u, v /= rs.v, w /= rs.w); return *this; }
FI XYZEval<T>& operator+=(const T &p) { LOGICAL_AXIS_CODE(e += p, x += p, y += p, z += p, i += p, j += p, k += p, u += p, v += p, w += p); return *this; }
FI XYZEval<T>& operator-=(const T &p) { LOGICAL_AXIS_CODE(e -= p, x -= p, y -= p, z -= p, i -= p, j -= p, k -= p, u -= p, v -= p, w -= p); return *this; }
FI XYZEval<T>& operator*=(const T &p) { LOGICAL_AXIS_CODE(e *= p, x *= p, y *= p, z *= p, i *= p, j *= p, k *= p, u *= p, v *= p, w *= p); return *this; }
FI XYZEval<T>& operator/=(const T &p) { LOGICAL_AXIS_CODE(e /= p, x /= p, y /= p, z /= p, i /= p, j /= p, k /= p, u /= p, v /= p, w /= p); return *this; }
FI XYZEval<T>& operator>>=(const int &p) { LOGICAL_AXIS_CODE(_RSE(e), _RSE(x), _RSE(y), _RSE(z), _RSE(i), _RSE(j), _RSE(k), _RSE(u), _RSE(v), _RSE(w)); return *this; }
FI XYZEval<T>& operator<<=(const int &p) { LOGICAL_AXIS_CODE(_LSE(e), _LSE(x), _LSE(y), _LSE(z), _LSE(i), _LSE(j), _LSE(k), _LSE(u), _LSE(v), _LSE(w)); return *this; }

View file

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

View file

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

View file

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

View file

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

View file

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

View file

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

View file

@ -32,7 +32,6 @@
#include "../../../module/delta.h"
#endif
#include "../../../MarlinCore.h"
#include <math.h>
//#define DEBUG_UBL_MOTION

View file

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

View file

@ -10,7 +10,6 @@
#include "dac_dac084s085.h"
#include "../../MarlinCore.h"
#include "../../HAL/shared/Delay.h"
dac084s085::dac084s085() { }

View file

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

View file

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

View file

@ -86,6 +86,8 @@ public:
static void update(State &state, const uint8_t c);
static bool isEnabled() { return enabled; }
private:
static bool enabled;
};

View file

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

View file

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

View file

@ -42,62 +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)
#if HAS_E0_FAN_TACHO
_TACHINIT(0);
#endif
#if HAS_E1_FAN_TACHO
_TACHINIT(1);
#endif
#if HAS_E2_FAN_TACHO
_TACHINIT(2);
#endif
#if HAS_E3_FAN_TACHO
_TACHINIT(3);
#endif
#if HAS_E4_FAN_TACHO
_TACHINIT(4);
#endif
#if HAS_E5_FAN_TACHO
_TACHINIT(5);
#endif
#if HAS_E6_FAN_TACHO
_TACHINIT(6);
#endif
#if HAS_E7_FAN_TACHO
_TACHINIT(7);
#endif
#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) {
#if HAS_E0_FAN_TACHO
_TACHO_CASE(0)
#endif
#if HAS_E1_FAN_TACHO
_TACHO_CASE(1)
#endif
#if HAS_E2_FAN_TACHO
_TACHO_CASE(2)
#endif
#if HAS_E3_FAN_TACHO
_TACHO_CASE(3)
#endif
#if HAS_E4_FAN_TACHO
_TACHO_CASE(4)
#endif
#if HAS_E5_FAN_TACHO
_TACHO_CASE(5)
#endif
#if HAS_E6_FAN_TACHO
_TACHO_CASE(6)
#endif
#if HAS_E7_FAN_TACHO
_TACHO_CASE(7)
#endif
REPEAT(8, _TACHO_GET_STATUS)
default: continue;
}
@ -115,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;
@ -143,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();
}
@ -156,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;
}
@ -179,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 ");

View file

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

View file

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

View file

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

View file

@ -67,18 +67,10 @@ Joystick joystick;
#if ENABLED(JOYSTICK_DEBUG)
void Joystick::report() {
SERIAL_ECHOPGM("Joystick");
#if HAS_JOY_ADC_X
SERIAL_ECHOPGM_P(SP_X_STR, JOY_X(x.getraw()));
#endif
#if HAS_JOY_ADC_Y
SERIAL_ECHOPGM_P(SP_Y_STR, JOY_Y(y.getraw()));
#endif
#if HAS_JOY_ADC_Z
SERIAL_ECHOPGM_P(SP_Z_STR, JOY_Z(z.getraw()));
#endif
#if HAS_JOY_ADC_EN
SERIAL_ECHO_TERNARY(READ(JOY_EN_PIN), " EN=", "HIGH (dis", "LOW (en", "abled)");
#endif
TERF(HAS_JOY_ADC_X, SERIAL_ECHOPGM_P)(SP_X_STR, JOY_X(x.getraw()));
TERF(HAS_JOY_ADC_Y, SERIAL_ECHOPGM_P)(SP_Y_STR, JOY_Y(y.getraw()));
TERF(HAS_JOY_ADC_Z, SERIAL_ECHOPGM_P)(SP_Z_STR, JOY_Z(z.getraw()));
TERF(HAS_JOY_ADC_EN, SERIAL_ECHO_TERNARY)(READ(JOY_EN_PIN), " EN=", "HIGH (dis", "LOW (en", "abled)");
SERIAL_EOL();
}
#endif

View file

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

View file

@ -24,7 +24,6 @@
#if HAS_PRUSA_MMU1
#include "../../MarlinCore.h"
#include "../../module/planner.h"
#include "../../module/stepper.h"

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