Compare commits

...

10 commits

Author SHA1 Message Date
e0f6c71071 Copy most settings from stock Creality older version 2025-06-20 18:52:49 -07:00
thinkyhead
62bb61b3d9 [cron] Bump distribution date (2025-06-17)
Some checks are pending
CI - Build Tests / Build Test (STM32F103VE_longer_maple) (push) Waiting to run
CI - Build Tests / Build Test (STM32F401RC_creality) (push) Waiting to run
CI - Build Tests / Build Test (STM32F407VE_black) (push) Waiting to run
CI - Build Tests / Build Test (STM32F446VE_fysetc) (push) Waiting to run
CI - Build Tests / Build Test (STM32G0B1RE_btt) (push) Waiting to run
CI - Build Tests / Build Test (STM32H743VI_btt) (push) Waiting to run
CI - Build Tests / Build Test (at90usb1286_dfu) (push) Waiting to run
CI - Build Tests / Build Test (chitu_f103) (push) Waiting to run
CI - Build Tests / Build Test (esp32) (push) Waiting to run
CI - Build Tests / Build Test (jgaurora_a5s_a1_maple) (push) Waiting to run
CI - Build Tests / Build Test (linux_native) (push) Waiting to run
CI - Build Tests / Build Test (malyan_M300) (push) Waiting to run
CI - Build Tests / Build Test (mega1280) (push) Waiting to run
CI - Build Tests / Build Test (mega2560) (push) Waiting to run
CI - Build Tests / Build Test (melzi_optiboot) (push) Waiting to run
CI - Build Tests / Build Test (mks_robin) (push) Waiting to run
CI - Build Tests / Build Test (mks_robin_lite_maple) (push) Waiting to run
CI - Build Tests / Build Test (mks_robin_nano_v1v2) (push) Waiting to run
CI - Build Tests / Build Test (mks_robin_pro2) (push) Waiting to run
CI - Build Tests / Build Test (mks_robin_pro_maple) (push) Waiting to run
CI - Build Tests / Build Test (mks_tinybee) (push) Waiting to run
CI - Build Tests / Build Test (rambo) (push) Waiting to run
CI - Build Tests / Build Test (rumba32) (push) Waiting to run
CI - Build Tests / Build Test (sanguino1284p) (push) Waiting to run
CI - Build Tests / Build Test (sanguino644p) (push) Waiting to run
CI - Build Tests / Build Test (simulator_linux_release) (push) Waiting to run
CI - Build Tests / Build Test (teensy31) (push) Waiting to run
CI - Build Tests / Build Test (teensy35) (push) Waiting to run
CI - Build Tests / Build Test (teensy41) (push) Waiting to run
CI - Unit Tests / Unit Test (push) Waiting to run
2025-06-17 00:32:42 +00:00
Andrew
a7f12169b9
📝 Review & update G-code comments (#27921) 2025-06-16 14:23:17 -05:00
thinkyhead
29ceba972c [cron] Bump distribution date (2025-06-15) 2025-06-15 00:36:55 +00:00
Keith Bennett
7965e066c7
🧑‍💻 Some TMC2240 updates (2) (#27919)
Followup to #27901
2025-06-14 16:22:29 -05:00
ellensp
f499735280
🩹 Fix Ender-3 S1 pin EXP3-4 (#27915) 2025-06-13 22:27:05 -05:00
Scott Lahteine
1e03f696f5
🧑‍💻 Some TMC2240 updates (#27901) 2025-06-13 22:13:09 -05:00
thinkyhead
7ac308fe4d [cron] Bump distribution date (2025-06-14) 2025-06-14 00:31:29 +00:00
Scott Lahteine
54a7ce999f 🎨 Update MPC sanity checka
Followup to #27911
2025-06-13 19:28:45 -05:00
tombrazier
89416a583c
MPC_PTC (#27911) 2025-06-13 19:10:03 -05:00
56 changed files with 840 additions and 633 deletions

View file

@ -61,14 +61,15 @@
// @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 "Ender-3 Pro" // Original author or contributor.
//#define CUSTOM_VERSION_FILE Version.h // Path from the root directory (no quotes)
// @section machine
#define SHOW_BOOTSCREEN
// Choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_RAMPS_14_EFB
#define MOTHERBOARD BOARD_MELZI_CREALITY
#endif
// @section serial
@ -94,7 +95,7 @@
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000, 500000, 1000000]
*/
#define BAUDRATE 250000
#define BAUDRATE 115200
//#define BAUD_RATE_GCODE // Enable G-code M575 to set the baud rate
@ -130,6 +131,7 @@
// Name displayed in the LCD "Ready" message and Info menu
//#define CUSTOM_MACHINE_NAME "3D Printer"
//#define CONFIGURABLE_MACHINE_NAME // Add G-code M550 to set/report the machine name
#define CUSTOM_MACHINE_NAME "Ender-3 Pro S"
// Printer's unique ID, used by some programs to differentiate between machines.
// Choose your own or use a service like https://www.uuidgenerator.net/version4
@ -148,9 +150,9 @@
* Options: A4988, A5984, DRV8825, LV8729, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2160, TMC2160_STANDALONE,
* TMC2208, TMC2208_STANDALONE, TMC2209, TMC2209_STANDALONE,
* TMC2240, TMC2240_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC2240, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE, TMC5160, TMC5160_STANDALONE
* :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC2240', 'TMC2240_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE']
* :['A4988', 'A5984', 'DRV8825', 'LV8729', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2160', 'TMC2160_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC2209', 'TMC2209_STANDALONE', 'TMC2240', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE', 'TMC5160', 'TMC5160_STANDALONE']
*/
#define X_DRIVER_TYPE A4988
#define Y_DRIVER_TYPE A4988
@ -735,7 +737,12 @@
//#define MPC_AUTOTUNE_MENU // Add MPC auto-tuning to the "Advanced Settings" menu. (~350 bytes of flash)
#define MPC_MAX 255 // (0..255) Current to nozzle while MPC is active.
#define MPC_HEATER_POWER { 40.0f } // (W) Heat cartridge powers.
#define MPC_HEATER_POWER { 40.0f } // (W) Nominal heat cartridge powers.
//#define MPC_PTC // Hotend power changes with temperature (e.g., PTC heat cartridges).
#if ENABLED(MPC_PTC)
#define MPC_HEATER_ALPHA { 0.0028f } // Temperature coefficient of resistance of the heat cartridges.
#define MPC_HEATER_REFTEMP { 20 } // (°C) Reference temperature for MPC_HEATER_POWER and MPC_HEATER_ALPHA.
#endif
#define MPC_INCLUDE_FAN // Model the fan speed?
@ -1295,7 +1302,7 @@
* Override with M92 (when enabled below)
* X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 500 }
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 93 }
/**
* Enable support for M92. Disable to save at least ~530 bytes of flash.
@ -1307,7 +1314,7 @@
* Override with M203
* X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 }
//#define LIMITED_MAX_FR_EDITING // Limit edit via M203 or LCD to DEFAULT_MAX_FEEDRATE * 2
#if ENABLED(LIMITED_MAX_FR_EDITING)
@ -1320,7 +1327,7 @@
* Override with M201
* X, Y, Z [, I [, J [, K...]]], E0 [, E1[, E2...]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
#define DEFAULT_MAX_ACCELERATION { 500, 500, 100, 1000 }
//#define LIMITED_MAX_ACCEL_EDITING // Limit edit via M201 or LCD to DEFAULT_MAX_ACCELERATION * 2
#if ENABLED(LIMITED_MAX_ACCEL_EDITING)
@ -1335,9 +1342,9 @@
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 500 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk limits (mm/s)
@ -1347,11 +1354,12 @@
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
//#define CLASSIC_JERK
// Stock Ender 3 Pro has CLASSIC_JERK enabled
#define CLASSIC_JERK
#if ENABLED(CLASSIC_JERK)
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.3
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//#define DEFAULT_IJERK 0.3
//#define DEFAULT_JJERK 0.3
@ -1668,7 +1676,7 @@
// X and Y axis travel speed between probes.
// Leave undefined to use the average of the current XY homing feedrate.
#define XY_PROBE_FEEDRATE (133*60) // (mm/min)
#define XY_PROBE_FEEDRATE (3000) // (mm/min)
// Feedrate for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_FEEDRATE_FAST (4*60) // (mm/min)
@ -1752,8 +1760,8 @@
//#define PROBE_OFFSET_XMAX 50 // (mm)
//#define PROBE_OFFSET_YMIN -50 // (mm)
//#define PROBE_OFFSET_YMAX 50 // (mm)
//#define PROBE_OFFSET_ZMIN -20 // (mm)
//#define PROBE_OFFSET_ZMAX 20 // (mm)
#define PROBE_OFFSET_ZMIN -20 // (mm)
#define PROBE_OFFSET_ZMAX 20 // (mm)
// Enable the M48 repeatability test to test probe accuracy
//#define Z_MIN_PROBE_REPEATABILITY_TEST
@ -1826,7 +1834,7 @@
// @section motion
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
#define INVERT_X_DIR false
#define INVERT_X_DIR true // default false
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
//#define INVERT_I_DIR false
@ -1839,7 +1847,7 @@
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
#define INVERT_E0_DIR false
#define INVERT_E0_DIR true // default false
#define INVERT_E1_DIR false
#define INVERT_E2_DIR false
#define INVERT_E3_DIR false
@ -1898,8 +1906,8 @@
// @section geometry
// The size of the printable area
#define X_BED_SIZE 200
#define Y_BED_SIZE 200
#define X_BED_SIZE 235
#define Y_BED_SIZE 235
// Travel limits (linear=mm, rotational=°) after homing, corresponding to endstop positions.
#define X_MIN_POS 0
@ -1907,7 +1915,7 @@
#define Z_MIN_POS 0
#define X_MAX_POS X_BED_SIZE
#define Y_MAX_POS Y_BED_SIZE
#define Z_MAX_POS 200
#define Z_MAX_POS 250
//#define I_MIN_POS 0
//#define I_MAX_POS 50
//#define J_MIN_POS 0
@ -2449,9 +2457,9 @@
* M501 - Read settings from EEPROM. (i.e., Throw away unsaved changes)
* M502 - Revert settings to "factory" defaults. (Follow with M500 to init the EEPROM.)
*/
//#define EEPROM_SETTINGS // Persistent storage with M500 and M501
#define EEPROM_SETTINGS // Persistent storage with M500 and M501
//#define DISABLE_M503 // Saves ~2700 bytes of flash. Disable for release!
#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save flash.
// #define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save flash.
#define EEPROM_BOOT_SILENT // Keep M503 quiet and only give errors during first load
#if ENABLED(EEPROM_SETTINGS)
//#define EEPROM_AUTO_INIT // Init EEPROM automatically on any errors.
@ -2488,16 +2496,16 @@
// Preheat Constants - Up to 10 are supported without changes
//
#define PREHEAT_1_LABEL "PLA"
#define PREHEAT_1_TEMP_HOTEND 180
#define PREHEAT_1_TEMP_BED 70
#define PREHEAT_1_TEMP_CHAMBER 35
#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255
#define PREHEAT_1_TEMP_HOTEND 185 // default 180
#define PREHEAT_1_TEMP_BED 45 // default 70
// #define PREHEAT_1_TEMP_CHAMBER 35 // default 35
#define PREHEAT_1_FAN_SPEED 255 // Value from 0 to 255, default 0
#define PREHEAT_2_LABEL "ABS"
#define PREHEAT_2_TEMP_HOTEND 240
#define PREHEAT_2_TEMP_BED 110
#define PREHEAT_2_TEMP_CHAMBER 35
#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255
#define PREHEAT_2_TEMP_BED 70 // default 110
// #define PREHEAT_2_TEMP_CHAMBER 35 // default 35
#define PREHEAT_2_FAN_SPEED 255 // Value from 0 to 255, default 0
/**
* @section nozzle park
@ -2694,7 +2702,7 @@
* SD Card support is disabled by default. If your controller has an SD slot,
* you must uncomment the following option or it won't work.
*/
//#define SDSUPPORT
#define SDSUPPORT
/**
* SD CARD: ENABLE CRC
@ -3138,7 +3146,7 @@
//
// Connect to EXP1 on RAMPS and compatible boards.
//
//#define CR10_STOCKDISPLAY
#define CR10_STOCKDISPLAY
//
// Ender-2 OEM display, a variant of the MKS_MINI_12864

View file

@ -1394,7 +1394,7 @@
* Multi-stepping sends steps in bursts to reduce MCU usage for high step-rates.
* This allows higher feedrates than the MCU could otherwise support.
*/
#define MULTISTEPPING_LIMIT 16 //: [1, 2, 4, 8, 16, 32, 64, 128]
#define MULTISTEPPING_LIMIT 16 // :[1, 2, 4, 8, 16, 32, 64, 128]
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
@ -3031,12 +3031,11 @@
#define INTERPOLATE true
#if HAS_DRIVER(TMC2240)
#define TMC2240_CURRENT_RANGE 1 // RMS: { 0:'690mA', 1:'1410mA', 2:'2120mA', 3:'2110mA' }
// PEAK:{ 0:'1A', 1:'2A', 2:'3A', 3:'3A' }
// Determines max current. Lower is more internal current resolution. Higher runs cooler.
#define TMC2240_Rref 12000 // ('rref', 12000, minval=12000, maxval=60000)
#define TMC2240_SLOPE_CONTROL 0 // :{ 0:'100V/us', 1:'200V/us', 2:'400V/us', 3:'800V/us' }
// Lower is more silent. Higher runs cooler.
#define TMC2240_RREF 12000 // (Ω) 12000 .. 60000. (FLY TMC2240 = 12300)
// Max Current. Lower for more internal resolution. Raise to run cooler.
#define TMC2240_CURRENT_RANGE 1 // :{ 0:'RMS=690mA PEAK=1A', 1:'RMS=1410mA PEAK=2A', 2:'RMS=2120mA PEAK=3A', 3:'RMS=2110mA PEAK=3A' }
// Slope Control: Lower is more silent. Higher runs cooler.
#define TMC2240_SLOPE_CONTROL 0 // :{ 0:'100V/µs', 1:'200V/µs', 2:'400V/µs', 3:'800V/µs' }
#endif
#if AXIS_IS_TMC_CONFIG(X)
@ -3467,7 +3466,7 @@
* X/Y/Z_STALL_SENSITIVITY is the default stall threshold.
* Use M914 X Y Z to set the stall threshold at runtime:
*
* Sensitivity TMC2209/2240 Others
* Sensitivity TMC2209 Others
* HIGHEST 255 -64 (Too sensitive => False positive)
* LOWEST 0 63 (Too insensitive => No trigger)
*
@ -3486,7 +3485,7 @@
//#define SENSORLESS_HOMING // StallGuard capable drivers only
#if ANY(SENSORLESS_HOMING, SENSORLESS_PROBING)
// TMC2209/2240: 0...255. TMC2130: -64...63
// TMC2209: 0...255. TMC2130: -64...63
#define X_STALL_SENSITIVITY 8
#define X2_STALL_SENSITIVITY X_STALL_SENSITIVITY
#define Y_STALL_SENSITIVITY 8

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-06-11"
//#define STRING_DISTRIBUTION_DATE "2025-06-17"
/**
* The protocol for communication to the host. Protocol indicates communication

View file

@ -229,7 +229,7 @@ usb_iface_desc_t UDC_DESC_STORAGE *udc_get_interface_desc(void);
* - USB Device Controller (UDC) provides USB chapter 9 compliance
* - USB Device Interface (UDI) provides USB Class compliance
* - USB Device Driver (UDD) provides USB Driver for each Atmel MCU
*
* Many USB Device applications can be implemented on Atmel MCU.
* Atmel provides many application notes for different applications:
* - AVR4900, provides general information about Device Stack

View file

@ -39,7 +39,7 @@
#endif
#ifndef F
class __FlashStringHelper;
#define F(str) (reinterpret_cast<const __FlashStringHelper *>(PSTR(str)))
#define F(string_literal) (reinterpret_cast<const __FlashStringHelper *>(PSTR(string_literal)))
#endif
#ifndef _SFR_BYTE
#define _SFR_BYTE(n) (n)

View file

@ -42,7 +42,6 @@
#define _TMC2209 0x2209A
#define _TMC2209_STANDALONE 0x2209B
#define _TMC2240 0x2240A
#define _TMC2240_STANDALONE 0x2240B
#define _TMC2660 0x2660A
#define _TMC2660_STANDALONE 0x2660B
#define _TMC5130 0x5130A
@ -108,7 +107,7 @@
#if ( HAS_DRIVER(TMC2100) \
|| HAS_DRIVER(TMC2130_STANDALONE) || HAS_DRIVER(TMC2160_STANDALONE) \
|| HAS_DRIVER(TMC2208_STANDALONE) || HAS_DRIVER(TMC2209_STANDALONE) \
|| HAS_DRIVER(TMC2240_STANDALONE) || HAS_DRIVER(TMC2660_STANDALONE) \
|| HAS_DRIVER(TMC2660_STANDALONE) \
|| HAS_DRIVER(TMC5130_STANDALONE) || HAS_DRIVER(TMC5160_STANDALONE) )
#define HAS_TRINAMIC_STANDALONE 1
#endif

View file

@ -529,7 +529,7 @@ void PrintJobRecovery::resume() {
}
#endif
// Restore retract and hop state from an active `G10` command
// Restore retract and hop state from an active 'G10' command
#if ENABLED(FWRETRACT)
EXTRUDER_LOOP() {
if (info.retract[e] != 0.0) {

View file

@ -83,9 +83,7 @@
#if HAS_TMCX1X0
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2130Stepper &st) { return st.PWM_SCALE(); }
#endif
static uint32_t get_pwm_scale(TMC2130Stepper &st) { return st.PWM_SCALE(); }
static TMC_driver_data get_driver_data(TMC2130Stepper &st) {
constexpr uint8_t OT_bp = 25, OTPW_bp = 26;
@ -144,9 +142,7 @@
#if HAS_DRIVER(TMC2240)
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); }
#endif
static uint32_t get_pwm_scale(TMC2240Stepper &st) { return st.PWM_SCALE(); }
static TMC_driver_data get_driver_data(TMC2240Stepper &st) {
constexpr uint8_t OT_bp = 25, OTPW_bp = 26;
@ -205,9 +201,7 @@
#if HAS_TMC220x
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2208Stepper &st) { return st.pwm_scale_sum(); }
#endif
static uint32_t get_pwm_scale(TMC2208Stepper &st) { return st.pwm_scale_sum(); }
static TMC_driver_data get_driver_data(TMC2208Stepper &st) {
constexpr uint8_t OTPW_bp = 0, OT_bp = 1;
@ -242,9 +236,7 @@
#if HAS_DRIVER(TMC2660)
#if ENABLED(TMC_DEBUG)
static uint32_t get_pwm_scale(TMC2660Stepper) { return 0; }
#endif
static uint32_t get_pwm_scale(TMC2660Stepper) { return 0; }
static TMC_driver_data get_driver_data(TMC2660Stepper &st) {
constexpr uint8_t OT_bp = 1, OTPW_bp = 2;
@ -383,9 +375,9 @@
else if (st.otpw_count > 0) st.otpw_count = 0;
}
#if ENABLED(TMC_DEBUG)
if (need_debug_reporting) report_polled_driver_data(st, data);
#endif
if (need_debug_reporting) {
TERN_(TMC_DEBUG, report_polled_driver_data(st, data));
}
return should_step_down;
}
@ -518,7 +510,7 @@
TMC_TSTEP,
TMC_TPWMTHRS,
TMC_TPWMTHRS_MMS,
TMC_OTPW,
TMC_DEBUG_OTPW,
TMC_OTPW_TRIGGERED,
TMC_TOFF,
TMC_TBL,
@ -575,7 +567,9 @@
TMC_GET_DRVCTRL,
TMC_GET_DRVSTATUS,
TMC_GET_SGCSCONF,
TMC_GET_SMARTEN
TMC_GET_SMARTEN,
TMC_GET_SG4_THRS,
TMC_GET_SG4_RESULT
};
template<class TMC>
@ -603,6 +597,7 @@
static void print_true_or_false(const bool tf) { SERIAL_ECHO(TRUE_FALSE(tf)); }
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130)
// Additional tmc_status fields for 2130/5130 and related drivers
static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) {
switch (i) {
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
@ -614,6 +609,7 @@
}
#endif
#if HAS_TMCX1X0
// Additional tmc_parse_drv_status fields for 2130 and related drivers
static void _tmc_parse_drv_status(TMC2130Stepper &st, const TMC_drv_status_enum i) {
switch (i) {
case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break;
@ -626,18 +622,17 @@
#endif
#if HAS_DRIVER(TMC2160) || HAS_DRIVER(TMC5160)
// Additional tmc_status fields for 2160/5160 and related drivers
static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) {
switch (i) {
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
case TMC_STEALTHCHOP: print_true_or_false(st.en_pwm_mode()); break;
case TMC_GLOBAL_SCALER:
{
const uint16_t value = st.GLOBAL_SCALER();
SERIAL_ECHO(value ?: 256);
SERIAL_ECHOPGM("/256");
}
break;
case TMC_GLOBAL_SCALER: {
const uint16_t value = st.GLOBAL_SCALER();
SERIAL_ECHO(value ?: 256);
SERIAL_ECHOPGM("/256");
} break;
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
default: break;
}
@ -646,12 +641,16 @@
#if HAS_TMC220x
// Additional tmc_status fields for 2208/2224/2209 drivers
static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
switch (i) {
// PWM_SCALE
case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break;
case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break;
// PWM_AUTO
case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break;
case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break;
// CHOPCONF
case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break;
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
default: break;
@ -659,19 +658,20 @@
}
#if HAS_DRIVER(TMC2209)
// Additional tmc_status fields for 2209 drivers
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
static void _tmc_status(TMCMarlin<TMC2209Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const TMC_debug_enum i) {
switch (i) {
case TMC_SGT: SERIAL_ECHO(st.SGTHRS()); break;
case TMC_UART_ADDR: SERIAL_ECHO(st.get_address()); break;
default:
TMC2208Stepper *parent = &st;
_tmc_status(*parent, i);
_tmc_status(static_cast<TMC2208Stepper &>(st), i);
break;
}
}
#endif
// Additional tmc_parse_drv_status fields for 2208/2224/2209 drivers
static void _tmc_parse_drv_status(TMC2208Stepper &st, const TMC_drv_status_enum i) {
switch (i) {
case TMC_T157: if (st.t157()) SERIAL_CHAR('*'); break;
@ -686,10 +686,13 @@
}
#if HAS_DRIVER(TMC2209)
// Additional tmc_parse_drv_status fields for 2209 drivers
static void _tmc_parse_drv_status(TMC2209Stepper &st, const TMC_drv_status_enum i) {
switch (i) {
case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break;
default: _tmc_parse_drv_status(static_cast<TMC2208Stepper &>(st), i); break;
default:
_tmc_parse_drv_status(static_cast<TMC2208Stepper &>(st), i);
break;
}
}
#endif
@ -697,13 +700,38 @@
#endif // HAS_TMC220x
#if HAS_DRIVER(TMC2240)
static void _tmc_parse_drv_status(TMC2240Stepper, const TMC_drv_status_enum) { }
// Additional tmc_parse_drv_status fields for 2240 drivers
static void _tmc_parse_drv_status(TMC2240Stepper &st, const TMC_drv_status_enum i) {
switch (i) {
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break;
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break;
case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break;
case TMC_FSACTIVE: if (st.fsactive()) SERIAL_CHAR('*'); break;
case TMC_DRV_CS_ACTUAL: if (st.CS_ACTUAL()) SERIAL_CHAR('*'); break;
case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break;
//case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break;
case TMC_DEBUG_OTPW: print_true_or_false(st.otpw()); break;
//case TMC_S2GA: if (st.s2ga()) SERIAL_CHAR('*'); break;
//case TMC_S2GB: if (st.s2gb()) SERIAL_CHAR('*'); break;
//case TMC_OLA: if (st.ola()) SERIAL_CHAR('*'); break;
//case TMC_OLB: if (st.olb()) SERIAL_CHAR('*'); break;
case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break;
case TMC_STST: if (!st.stst()) SERIAL_CHAR('*'); break;
default: break; // other...
}
}
// Additional tmc_status fields for 2240 drivers
static void _tmc_status(TMC2240Stepper &st, const TMC_debug_enum i) {
switch (i) {
// PWM_SCALE
case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break;
case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break;
// PWM_AUTO
case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break;
case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break;
// CHOPCONF
case TMC_STEALTHCHOP: print_true_or_false(st.stealth()); break;
case TMC_INTERPOLATE: print_true_or_false(st.intpol()); break;
case TMC_VAIN: SERIAL_ECHO(st.get_ain_voltage()); break;
@ -714,7 +742,8 @@
default: break;
}
}
#endif
#endif // TMC2240
#if HAS_DRIVER(TMC2660)
static void _tmc_parse_drv_status(TMC2660Stepper, const TMC_drv_status_enum) { }
@ -750,14 +779,8 @@
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break;
case TMC_IRUN:
SERIAL_ECHO(st.irun());
SERIAL_ECHOPGM("/31");
break;
case TMC_IHOLD:
SERIAL_ECHO(st.ihold());
SERIAL_ECHOPGM("/31");
break;
case TMC_IRUN: SERIAL_ECHO(st.irun()); SERIAL_ECHOPGM("/31"); break;
case TMC_IHOLD: SERIAL_ECHO(st.ihold()); SERIAL_ECHOPGM("/31"); break;
case TMC_CS_ACTUAL: print_cs_actual(st); break;
case TMC_VSENSE: print_vsense(st); break;
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
@ -769,7 +792,7 @@
if (tpwmthrs_val) SERIAL_ECHO(tpwmthrs_val); else SERIAL_CHAR('-');
} break;
#endif
case TMC_OTPW: print_true_or_false(st.otpw()); break;
case TMC_DEBUG_OTPW: print_true_or_false(st.otpw()); break;
#if ENABLED(MONITOR_DRIVER_STATUS)
case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break;
#endif
@ -792,13 +815,10 @@
case TMC_CURRENT: SERIAL_ECHO(st.getMilliamps()); break;
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
case TMC_MAX_CURRENT: SERIAL_ECHO(p_float_t(st.rms_current() * 1.41, 0)); break;
case TMC_IRUN:
SERIAL_ECHO(st.cs());
SERIAL_ECHOPGM("/31");
break;
case TMC_IRUN: SERIAL_ECHO(st.cs()); SERIAL_ECHOPGM("/31"); break;
case TMC_VSENSE: SERIAL_ECHO(st.vsense() ? F("1=.165") : F("0=.310")); break;
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
//case TMC_OTPW: print_true_or_false(st.otpw()); break;
//case TMC_DEBUG_OTPW: print_true_or_false(st.otpw()); break;
//case TMC_OTPW_TRIGGERED: print_true_or_false(st.getOTPW()); break;
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
case TMC_TOFF: SERIAL_ECHO(st.toff()); break;
@ -808,30 +828,26 @@
default: _tmc_status(st, i); break;
}
}
#endif
#endif // TMC2660
template <typename TMC>
static void tmc_parse_drv_status(TMC &st, const TMC_drv_status_enum i) {
SERIAL_CHAR('\t');
switch (i) {
case TMC_DRV_CODES: st.printLabel(); break;
case TMC_STST: if (!st.stst()) SERIAL_CHAR('*'); break;
case TMC_OLB: if (st.olb()) SERIAL_CHAR('*'); break;
case TMC_OLA: if (st.ola()) SERIAL_CHAR('*'); break;
case TMC_S2GB: if (st.s2gb()) SERIAL_CHAR('*'); break;
case TMC_S2GA: if (st.s2ga()) SERIAL_CHAR('*'); break;
case TMC_DRV_OTPW: if (st.otpw()) SERIAL_CHAR('*'); break;
case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break;
case TMC_DRV_CODES: st.printLabel(); break;
case TMC_STST: if (!st.stst()) SERIAL_CHAR('*'); break;
case TMC_OLB: if (st.olb()) SERIAL_CHAR('*'); break;
case TMC_OLA: if (st.ola()) SERIAL_CHAR('*'); break;
case TMC_S2GB: if (st.s2gb()) SERIAL_CHAR('*'); break;
case TMC_S2GA: if (st.s2ga()) SERIAL_CHAR('*'); break;
case TMC_DRV_OTPW: if (st.otpw()) SERIAL_CHAR('*'); break;
case TMC_OT: if (st.ot()) SERIAL_CHAR('*'); break;
case TMC_DRV_STATUS_HEX: {
const uint32_t drv_status = st.DRV_STATUS();
SERIAL_CHAR('\t');
st.printLabel();
SERIAL_CHAR('\t');
print_hex_long(drv_status, ':', true);
SERIAL_CHAR('\t'); st.printLabel(); SERIAL_CHAR('\t'); print_hex_long(drv_status, ':', true);
if (drv_status == 0xFFFFFFFF || drv_status == 0) SERIAL_ECHOPGM("\t Bad response!");
SERIAL_EOL();
break;
}
} break;
default: _tmc_parse_drv_status(st, i); break;
}
}
@ -946,7 +962,7 @@
TMC_REPORT("tstep\t", TMC_TSTEP);
TMC_REPORT("PWM thresh.", TMC_TPWMTHRS);
TMC_REPORT("[mm/s]\t", TMC_TPWMTHRS_MMS);
TMC_REPORT("OT prewarn", TMC_OTPW);
TMC_REPORT("OT prewarn", TMC_DEBUG_OTPW);
#if ENABLED(MONITOR_DRIVER_STATUS)
TMC_REPORT("triggered\n OTP\t", TMC_OTPW_TRIGGERED);
#endif
@ -964,6 +980,7 @@
TMC_REPORT(" -start\t", TMC_HSTRT);
TMC_REPORT("Stallguard thrs", TMC_SGT);
TMC_REPORT("uStep count", TMC_MSCNT);
DRV_REPORT("DRVSTATUS", TMC_DRV_CODES);
#if HAS_TMCX1X0_OR_2240 || HAS_TMC220x
DRV_REPORT("sg_result", TMC_SG_RESULT);
@ -984,10 +1001,12 @@
DRV_REPORT("150C\t", TMC_T150);
DRV_REPORT("143C\t", TMC_T143);
DRV_REPORT("120C\t", TMC_T120);
#endif
#if HAS_TMC220x || HAS_DRIVER(TMC2240)
DRV_REPORT("s2vsa\t", TMC_S2VSA);
DRV_REPORT("s2vsb\t", TMC_S2VSB);
#endif
DRV_REPORT("Driver registers:\n",TMC_DRV_STATUS_HEX);
DRV_REPORT("Driver registers:\n", TMC_DRV_STATUS_HEX);
#if HAS_DRIVER(TMC2240)
TMC_REPORT("Analog in (v)", TMC_VAIN);
TMC_REPORT("Supply (v)", TMC_VSUPPLY);
@ -1035,6 +1054,7 @@
}
SERIAL_CHAR('\t');
}
#endif // HAS_TRINAMIC_CONFIG
#if HAS_DRIVER(TMC2660)

View file

@ -45,14 +45,14 @@
/**
* M420: Enable/Disable Bed Leveling and/or set the Z fade height.
*
* S[bool] Turns leveling on or off
* Z[height] Sets the Z fade height (0 or none to disable)
* V[bool] Verbose - Print the leveling grid
* S<bool> Turns leveling on or off
* Z<height> Sets the Z fade height (0 or none to disable)
* V<bool> Verbose - Print the leveling grid
*
* With AUTO_BED_LEVELING_UBL only:
*
* L[index] Load UBL mesh from index (0 is default)
* T[map] 0:Human-readable 1:CSV 2:"LCD" 4:Compact
* L<index> Load UBL mesh from index (0 is default)
* T<map> 0:Human-readable 1:CSV 2:"LCD" 4:Compact
*
* With mesh-based leveling only:
*

View file

@ -156,81 +156,72 @@ public:
#endif
/**
* G29: Detailed Z probe, probes the bed at 3 or more points.
* Will fail if the printer has not been homed with G28.
* G29: Bed Leveling
*
* Enhanced G29 Auto Bed Leveling Probe Routine
* Enhanced G29 Auto Bed Leveling Probe Routine.
* Probes the bed at 3 or more points.
* Will fail if the printer has not been homed with G28.
*
* O Auto-level only if needed
* Parameters:
* O Auto-level only if needed (Optional)
*
* D Dry-Run mode. Just evaluate the bed Topology - Don't apply
* or alter the bed level data. Useful to check the topology
* after a first run of G29.
* D<bool> Dry-Run mode. Just evaluate the bed Topology -
* Don't apply or alter the bed level data.
* Useful to check the topology after a first run of G29.
*
* J Jettison current bed leveling data
* J<bool> Jettison current bed leveling data
*
* V Set the verbose level (0-4). Example: "G29 V3"
* V<0-4> Set the verbose level (0-4)
* Example: G29 V3
*
* Parameters With LINEAR leveling only:
* With AUTO_BED_LEVELING_LINEAR:
* P<int> Set the size of the grid that will be probed (P x P points)
* Example: G29 P4
*
* P Set the size of the grid that will be probed (P x P points).
* Example: "G29 P4"
* X<int> Set the X size of the grid that will be probed (X x Y points)
* Example: G29 X7 Y5
*
* X Set the X size of the grid that will be probed (X x Y points).
* Example: "G29 X7 Y5"
* Y<int> Set the Y size of the grid that will be probed (X x Y points)
*
* Y Set the Y size of the grid that will be probed (X x Y points).
* T Generate a Bed Topology Report
* Example: G29 P5 T - for a detailed report.
* This is useful for manual bed leveling and finding flaws in the bed
* (to assist with part placement).
* Not supported by non-linear delta printer bed leveling.
*
* T Generate a Bed Topology Report. Example: "G29 P5 T" for a detailed report.
* This is useful for manual bed leveling and finding flaws in the bed (to
* assist with part placement).
* Not supported by non-linear delta printer bed leveling.
* With AUTO_BED_LEVELING_LINEAR and AUTO_BED_LEVELING_BILINEAR:
* S<rate> Set the XY travel speed between probe points (in units/min)
* H<linear> Set bounds to a centered square H x H units in size
* -or-
* F<linear> Set the Front limit of the probing grid
* B<linear> Set the Back limit of the probing grid
* L<linear> Set the Left limit of the probing grid
* R<linear> Set the Right limit of the probing grid
*
* Parameters With LINEAR and BILINEAR leveling only:
* With AUTO_BED_LEVELING_BILINEAR:
* Z<float> Supply additional Z offset to all probe points.
* W<bool> Write a mesh point. (If G29 is idle.)
* I<index> Index for mesh point
* J<index> Index for mesh point
* X<float> For mesh point, overrides I
* Y<float> For mesh point, overrides J
* Z<float> For mesh point. If omitted, uses current position's raw Z
*
* S Set the XY travel speed between probe points (in units/min)
* With DEBUG_LEVELING_FEATURE:
* C<bool> Make a totally fake grid with no actual probing.
* For use in testing when no probing is possible.
*
* H Set bounds to a centered square H x H units in size
* With PROBE_MANUALLY:
* To do manual probing simply repeat G29 until the procedure is complete.
* The first G29 accepts parameters. 'G29 Q' for status, 'G29 A' to abort.
*
* -or-
* Q<bool> Query leveling and G29 state
* A<bool> Abort current leveling procedure
*
* F Set the Front limit of the probing grid
* B Set the Back limit of the probing grid
* L Set the Left limit of the probing grid
* R Set the Right limit of the probing grid
*
* Parameters with DEBUG_LEVELING_FEATURE only:
*
* C Make a totally fake grid with no actual probing.
* For use in testing when no probing is possible.
*
* Parameters with BILINEAR leveling only:
*
* Z Supply an additional Z probe offset
*
* Extra parameters with PROBE_MANUALLY:
*
* To do manual probing simply repeat G29 until the procedure is complete.
* The first G29 accepts parameters. 'G29 Q' for status, 'G29 A' to abort.
*
* Q Query leveling and G29 state
*
* A Abort current leveling procedure
*
* Extra parameters with BILINEAR only:
*
* W Write a mesh point. (If G29 is idle.)
* I X index for mesh point
* J Y index for mesh point
* X X for mesh point, overrides I
* Y Y for mesh point, overrides J
* Z Z for mesh point. Otherwise, raw current Z.
*
* Without PROBE_MANUALLY:
*
* E By default G29 will engage the Z probe, test the bed, then disengage.
* Include "E" to engage/disengage the Z probe for each sample.
* There's no extra effect if you have a fixed Z probe.
* Without PROBE_MANUALLY:
* E<bool> By default G29 will engage the Z probe, test the bed, then disengage
* Include "E" to engage/disengage the Z probe for each sample.
* There's no extra effect if you have a fixed Z probe.
*/
G29_TYPE GcodeSuite::G29() {
@ -855,15 +846,15 @@ G29_TYPE GcodeSuite::G29() {
}
#endif // !PROBE_MANUALLY
//
// G29 Finishing Code
//
// Unless this is a dry run, auto bed leveling will
// definitely be enabled after this point.
//
// If code above wants to continue leveling, it should
// return or loop before this point.
//
/**
* G29 Finishing Code
*
* Unless this is a dry run, auto bed leveling will
* definitely be enabled after this point.
*
* If code above wants to continue leveling, it should
* return or loop before this point.
*/
if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position);
@ -892,12 +883,12 @@ G29_TYPE GcodeSuite::G29() {
// For LINEAR leveling calculate matrix, print reports, correct the position
/**
* solve the plane equation ax + by + d = z
* Solve the plane equation ax + by + d = z
* A is the matrix with rows [x y 1] for all the probed points
* B is the vector of the Z positions
* the normal vector to the plane is formed by the coefficients of the
* The normal vector to the plane is formed by the coefficients of the
* plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0
* so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
* so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z).
*/
struct { float a, b, d; } plane_equation_coefficients;

View file

@ -200,11 +200,12 @@
#endif // IMPROVE_HOMING_RELIABILITY
/**
* G28: Home all axes according to settings
* G28: Auto Home
*
* Parameters
* Home all axes according to settings
*
* None Home to all axes with no parameters.
* Parameters:
* None Home all axes
* With QUICK_HOME enabled XY will home together, then Z.
*
* L<bool> Force leveling state ON (if possible) or OFF after homing (Requires RESTORE_LEVELING_AFTER_G28 or ENABLE_LEVELING_AFTER_G28)
@ -216,7 +217,7 @@
* fail with position unreachable due to probe/nozzle offset. This
* can be used to avoid a model.
*
* Cartesian/SCARA parameters
* Cartesian/SCARA parameters:
*
* X Home to the X endstop
* Y Home to the Y endstop

View file

@ -41,8 +41,8 @@
constexpr uint8_t _7P_STEP = 1, // 7-point step - to change number of calibration points
_4P_STEP = _7P_STEP * 2, // 4-point step
NPP = _7P_STEP * 6; // number of calibration points on the radius
enum CalEnum : char { // the 7 main calibration points - add definitions if needed
NPP = _7P_STEP * 6; // Number of calibration points on the radius
enum CalEnum : char { // The 7 main calibration points - add definitions if needed
CEN = 0,
__A = 1,
_AB = __A + _7P_STEP,
@ -197,13 +197,13 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi
if (!_0p_calibration) {
if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // probe the center
if (!_7p_no_intermediates && !_7p_4_intermediates && !_7p_11_intermediates) { // Probe the center
const xy_pos_t center{0};
z_pt[CEN] += calibration_probe(center, stow_after_each, probe_at_offset);
if (isnan(z_pt[CEN])) return false;
}
if (_7p_calibration) { // probe extra center points
if (_7p_calibration) { // Probe extra center points
const float start = _7p_9_center ? float(_CA) + _7P_STEP / 3.0f : _7p_6_center ? float(_CA) : float(__C),
steps = _7p_9_center ? _4P_STEP / 3.0f : _7p_6_center ? _7P_STEP : _4P_STEP;
I_LOOP_CAL_PT(rad, start, steps) {
@ -216,7 +216,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi
z_pt[CEN] /= float(_7p_2_intermediates ? 7 : probe_points);
}
if (!_1p_calibration) { // probe the radius
if (!_1p_calibration) { // Probe the radius
const CalEnum start = _4p_opposite_points ? _AB : __A;
const float steps = _7p_14_intermediates ? _7P_STEP / 15.0f : // 15r * 6 + 10c = 100
_7p_11_intermediates ? _7P_STEP / 12.0f : // 12r * 6 + 9c = 81
@ -254,10 +254,11 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi
}
/**
* kinematics routines and auto tune matrix scaling parameters:
* see https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for
* - formulae for approximative forward kinematics in the end-stop displacement matrix
* - definition of the matrix scaling parameters
* Kinematics routines and auto tune matrix scaling parameters
*
* NOTE: See https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for:
* - Formula for approximative forward kinematics in the end-stop displacement matrix
* - Definition of the matrix scaling parameters
*/
static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1], const float dcr) {
xyz_pos_t pos{0};
@ -346,43 +347,43 @@ static float auto_tune_a(const float dcr) {
}
/**
* G33 - Delta '1-4-7-point' Auto-Calibration
* Calibrate height, z_offset, endstops, delta radius, and tower angles.
* G33: Delta Auto Calibration
*
* Calibrate height, z_offset, endstops, delta radius, and tower angles.
*
* Parameters:
* P<int> Number of probe points:
* P0 Normalizes end-stops and tower angle corrections only (no probing)
* P1 Probe center and set height only
* P2 Probe center and towers. Set height, endstops, and delta radius
* P3 Probe all positions - center, towers and opposite towers. Set all
* P4-P10 Probe all positions with intermediate locations, averaging them
*
* Pn Number of probe points:
* P0 Normalizes calibration.
* P1 Calibrates height only with center probe.
* P2 Probe center and towers. Calibrate height, endstops and delta radius.
* P3 Probe all positions: center, towers and opposite towers. Calibrate all.
* P4-P10 Probe all positions at different intermediate locations and average them.
* R<float> Temporarily reduce the size of the probe grid by the specified amount
*
* Rn.nn Temporary reduce the probe grid by the specified amount (mm)
* T<bool> Disable tower angle corrections calibration (P3-P7)
*
* T Don't calibrate tower angle corrections
* C<float> Calibration precision; if omitted iterations stop at best achievable precision
*
* Cn.nn Calibration precision; when omitted calibrates to maximum precision
* F<1-30> Run (force) this number of iterations and take the best result
*
* Fn Force to run at least n iterations and take the best result
* V<int> Verbose level:
* V0 Dry-run mode. Report settings and probe results. No calibration
* V1 Report start and end settings only
* V2 Report settings at each iteration
* V3 Report settings and probe results
*
* Vn Verbose level:
* V0 Dry-run mode. Report settings and probe results. No calibration.
* V1 Report start and end settings only
* V2 Report settings at each iteration
* V3 Report settings and probe results
* E<bool> Engage the probe for each point
*
* E Engage the probe for each point
* O<bool> Probe at probe-offset-relative positions instead of the required kinematic points
*
* O Probe at offsetted probe positions (this is wrong but it seems to work)
*
* With SENSORLESS_PROBING:
* Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.)
* X Don't activate stallguard on X.
* Y Don't activate stallguard on Y.
* Z Don't activate stallguard on Z.
*
* S Save offset_sensorless_adj
* With HAS_DELTA_SENSORLESS_PROBING:
* Use these flags to calibrate stall sensitivity:
* Example: G33 P1 Y Z - to calibrate X only
* X Don't activate stallguard on X
* Y Don't activate stallguard on Y
* Z Don't activate stallguard on Z
* S Save offset_sensorless_adj
*/
void GcodeSuite::G33() {
@ -481,11 +482,11 @@ void GcodeSuite::G33() {
caltower({ false, true, false }); // B
caltower({ false, false, true }); // C
probe.test_sensitivity = { true, true, true }; // reset to all
probe.test_sensitivity = { true, true, true }; // Reset to all
}
#endif
do { // start iterations
do { // Start iterations
float z_at_pt[NPP + 1] = { 0.0f };
@ -505,11 +506,11 @@ void GcodeSuite::G33() {
if ((zero_std_dev < test_precision || iterations <= force_iterations) && zero_std_dev > calibration_precision) {
#if !HAS_BED_PROBE
test_precision = 0.0f; // forced end
test_precision = 0.0f; // Forced end
#endif
if (zero_std_dev < zero_std_dev_min) {
// set roll-back point
// Set roll-back point
e_old = delta_endstop_adj;
r_old = delta_radius;
h_old = delta_height;
@ -520,10 +521,11 @@ void GcodeSuite::G33() {
float r_delta = 0.0f;
/**
* convergence matrices:
* see https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for
* - definition of the matrix scaling parameters
* - matrices for 4 and 7 point calibration
* Convergence matrices
*
* NOTE: See https://github.com/LVD-AC/Marlin-AC/tree/1.1.x-AC/documentation for:
* - Definition of the matrix scaling parameters
* - Matrices for 4 and 7 point calibration
*/
#define ZP(N,I) ((N) * z_at_pt[I] / 4.0f) // 4.0 = divider to normalize to integers
#define Z12(I) ZP(12, I)
@ -532,7 +534,7 @@ void GcodeSuite::G33() {
#define Z1(I) ZP(1, I)
#define Z0(I) ZP(0, I)
// calculate factors
// Calculate factors
if (_7p_9_center) dcr *= 0.9f;
h_factor = auto_tune_h(dcr);
r_factor = auto_tune_r(dcr);
@ -541,22 +543,22 @@ void GcodeSuite::G33() {
switch (probe_points) {
case 0:
test_precision = 0.0f; // forced end
test_precision = 0.0f; // Forced end
break;
case 1:
test_precision = 0.0f; // forced end
test_precision = 0.0f; // Forced end
LOOP_NUM_AXES(axis) e_delta[axis] = +Z4(CEN);
break;
case 2:
if (towers_set) { // see 4 point calibration (towers) matrix
if (towers_set) { // See 4 point calibration (towers) matrix
e_delta.set((+Z4(__A) -Z2(__B) -Z2(__C)) * h_factor +Z4(CEN),
(-Z2(__A) +Z4(__B) -Z2(__C)) * h_factor +Z4(CEN),
(-Z2(__A) -Z2(__B) +Z4(__C)) * h_factor +Z4(CEN));
r_delta = (+Z4(__A) +Z4(__B) +Z4(__C) -Z12(CEN)) * r_factor;
}
else { // see 4 point calibration (opposites) matrix
else { // See 4 point calibration (opposites) matrix
e_delta.set((-Z4(_BC) +Z2(_CA) +Z2(_AB)) * h_factor +Z4(CEN),
(+Z2(_BC) -Z4(_CA) +Z2(_AB)) * h_factor +Z4(CEN),
(+Z2(_BC) +Z2(_CA) -Z4(_AB)) * h_factor +Z4(CEN));
@ -564,13 +566,13 @@ void GcodeSuite::G33() {
}
break;
default: // see 7 point calibration (towers & opposites) matrix
default: // See 7 point calibration (towers & opposites) matrix
e_delta.set((+Z2(__A) -Z1(__B) -Z1(__C) -Z2(_BC) +Z1(_CA) +Z1(_AB)) * h_factor +Z4(CEN),
(-Z1(__A) +Z2(__B) -Z1(__C) +Z1(_BC) -Z2(_CA) +Z1(_AB)) * h_factor +Z4(CEN),
(-Z1(__A) -Z1(__B) +Z2(__C) +Z1(_BC) +Z1(_CA) -Z2(_AB)) * h_factor +Z4(CEN));
r_delta = (+Z2(__A) +Z2(__B) +Z2(__C) +Z2(_BC) +Z2(_CA) +Z2(_AB) -Z12(CEN)) * r_factor;
if (towers_set) { // see 7 point tower angle calibration (towers & opposites) matrix
if (towers_set) { // See 7 point tower angle calibration (towers & opposites) matrix
t_delta.set((+Z0(__A) -Z4(__B) +Z4(__C) +Z0(_BC) -Z4(_CA) +Z4(_AB) +Z0(CEN)) * a_factor,
(+Z4(__A) +Z0(__B) -Z4(__C) +Z4(_BC) +Z0(_CA) -Z4(_AB) +Z0(CEN)) * a_factor,
(-Z4(__A) +Z4(__B) +Z0(__C) -Z4(_BC) +Z4(_CA) +Z0(_AB) +Z0(CEN)) * a_factor);
@ -582,14 +584,14 @@ void GcodeSuite::G33() {
delta_tower_angle_trim += t_delta;
}
else if (zero_std_dev >= test_precision) {
// roll back
// Roll back
delta_endstop_adj = e_old;
delta_radius = r_old;
delta_height = h_old;
delta_tower_angle_trim = a_old;
}
if (verbose_level != 0) { // !dry run
if (verbose_level != 0) { // !Dry-run
// Normalize angles to least-squares
if (_angle_results) {
@ -620,7 +622,7 @@ void GcodeSuite::G33() {
#endif
}
if (verbose_level != 0) { // !dry run
if (verbose_level != 0) { // !Dry-run
if ((zero_std_dev >= test_precision && iterations > force_iterations) || zero_std_dev <= calibration_precision) { // end iterations
SERIAL_ECHOPGM("Calibration OK");
SERIAL_ECHO_SP(32);
@ -657,7 +659,7 @@ void GcodeSuite::G33() {
print_calibration_settings(_endstop_results, _angle_results);
}
}
else { // dry run
else { // Dry-run
FSTR_P const enddryrun = F("End DRY-RUN");
SERIAL_ECHO(enddryrun);
SERIAL_ECHO_SP(35);

View file

@ -40,7 +40,9 @@
#include "../../core/debug_out.h"
/**
* G34 - Align the ends of the X gantry. See https://youtu.be/3jAFQdTk8iw
* G34: Mechanical Gantry Calibration
*
* Align the ends of the X gantry. See https://youtu.be/3jAFQdTk8iw
*
* - The carriage moves to GANTRY_CALIBRATION_SAFE_POSITION, also called the pounce position.
* - If possible, the Z stepper current is reduced to the value specified by 'S'
@ -53,8 +55,8 @@
* - The machine is re-homed, according to GANTRY_CALIBRATION_COMMANDS_POST.
*
* Parameters:
* [S<mA>] - Current value to use for the raise move. (Default: GANTRY_CALIBRATION_CURRENT)
* [Z<linear>] - Extra distance past Z_MAX_POS to move the Z axis. (Default: GANTRY_CALIBRATION_EXTRA_HEIGHT)
* S<mA> Current value to use for the raise move. (Default: GANTRY_CALIBRATION_CURRENT)
* Z<linear> Extra distance past Z_MAX_POS to move the Z axis. (Default: GANTRY_CALIBRATION_EXTRA_HEIGHT)
*/
void GcodeSuite::G34() {

View file

@ -56,23 +56,24 @@
#endif
/**
* G34: Z-Stepper automatic alignment
* G34: Z Steppers Auto-Alignment
*
* Manual stepper lock controls (reset by G28):
* L Unlock all steppers
* Z<1-4> Z stepper to lock / unlock
* S<state> 0=UNLOCKED 1=LOCKED. If omitted, assume LOCKED.
* Parameters:
* Manual stepper lock controls (reset by G28):
* L Unlock all steppers
* Z<int> Target specific Z stepper to lock/unlock (1-4)
* S<bool> Lock state; 0=UNLOCKED 1=LOCKED. If omitted, assume LOCKED
*
* Examples:
* G34 Z1 ; Lock Z1
* G34 L Z2 ; Unlock all, then lock Z2
* G34 Z2 S0 ; Unlock Z2
* With Z_STEPPER_AUTO_ALIGN:
* I<int> Number of test iterations. If omitted, Z_STEPPER_ALIGN_ITERATIONS. (1-30)
* T<float> Target Accuracy factor. If omitted, Z_STEPPER_ALIGN_ACC. (0.01-1.0)
* A<float> Provide an Amplification value. If omitted, Z_STEPPER_ALIGN_AMP. (0.5-2.0)
* R Recalculate points based on current probe offsets
*
* With Z_STEPPER_AUTO_ALIGN:
* I<iterations> Number of tests. If omitted, Z_STEPPER_ALIGN_ITERATIONS.
* T<accuracy> Target Accuracy factor. If omitted, Z_STEPPER_ALIGN_ACC.
* A<amplification> Provide an Amplification value. If omitted, Z_STEPPER_ALIGN_AMP.
* R Flag to recalculate points based on current probe offsets
* Example:
* G34 Z1 ; Lock Z1
* G34 L Z2 ; Unlock all, then lock Z2
* G34 Z2 S0 ; Unlock Z2
*/
void GcodeSuite::G34() {

View file

@ -38,47 +38,53 @@
#include "../../lcd/marlinui.h"
/**
* G76: calibrate probe and/or bed temperature offsets
* Notes:
* - When calibrating probe, bed temperature is held constant.
* Compensation values are deltas to first probe measurement at probe temp. = 30°C.
* - When calibrating bed, probe temperature is held constant.
* Compensation values are deltas to first probe measurement at bed temp. = 60°C.
* - The hotend will not be heated at any time.
* - On my Průša MK3S clone I put a piece of paper between the probe and the hotend
* so the hotend fan would not cool my probe constantly. Alternatively you could just
* make sure the fan is not running while running the calibration process.
* G76: Probe Temperature Calibration
*
* Probe calibration:
* - Moves probe to cooldown point.
* - Heats up bed to 100°C.
* - Moves probe to probing point (1mm above heatbed).
* - Waits until probe reaches target temperature (30°C).
* - Does a z-probing (=base value) and increases target temperature by 5°C.
* - Waits until probe reaches increased target temperature.
* - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C.
* - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further).
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
* While this is not exact by any means it is still better than simply using the last compensation value.
* Calibrate probe and/or bed temperature offsets.
*
* Bed calibration:
* - Moves probe to cooldown point.
* - Heats up bed to 60°C.
* - Moves probe to probing point (1mm above heatbed).
* - Waits until probe reaches target temperature (30°C).
* - Does a z-probing (=base value) and increases bed temperature by 5°C.
* - Moves probe to cooldown point.
* - Waits until probe is below 30°C and bed has reached target temperature.
* - Moves probe to probing point and waits until it reaches target temperature (30°C).
* - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C.
* - Repeats last four points until max. bed temperature reached (110°C) or timeout.
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
* While this is not exact by any means it is still better than simply using the last compensation value.
* Probe calibration:
* - Moves probe to cooldown point.
* - Heats up bed to 100°C.
* - Moves probe to probing point (1mm above heatbed).
* - Waits until probe reaches target temperature (30°C).
* - Does a z-probing (=base value) and increases target temperature by 5°C.
* - Waits until probe reaches increased target temperature.
* - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C.
* - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further).
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
* While this is not exact by any means it is still better than simply using the last compensation value.
*
* G76 [B | P]
* - no flag - Both calibration procedures will be run.
* - `B` - Run bed temperature calibration.
* - `P` - Run probe temperature calibration.
* Bed calibration:
* - Moves probe to cooldown point.
* - Heats up bed to 60°C.
* - Moves probe to probing point (1mm above heatbed).
* - Waits until probe reaches target temperature (30°C).
* - Does a z-probing (=base value) and increases bed temperature by 5°C.
* - Moves probe to cooldown point.
* - Waits until probe is below 30°C and bed has reached target temperature.
* - Moves probe to probing point and waits until it reaches target temperature (30°C).
* - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C.
* - Repeats last four points until max. bed temperature reached (110°C) or timeout.
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
* While this is not exact by any means it is still better than simply using the last compensation value.
*
* Usage:
* G76 [ B | P ]
*
* Parameters:
* None Run Both calibration procedures
* B Calibrate bed only
* P Calibrate probe only
*
* NOTES:
* - When calibrating probe, bed temperature is held constant.
* Compensation values are deltas to first probe measurement at probe temp. = 30°C.
* - When calibrating bed, probe temperature is held constant.
* Compensation values are deltas to first probe measurement at bed temp. = 60°C.
* - The hotend will not be heated at any time.
* - On my Průša MK3S clone I put a piece of paper between the probe and the hotend
* so the hotend fan would not cool my probe constantly. Alternatively you could just
* make sure the fan is not running while running the calibration process.
*/
#if ALL(PTC_PROBE, PTC_BED)
@ -291,22 +297,26 @@
#endif // PTC_PROBE && PTC_BED
/**
* M871: Report / reset temperature compensation offsets.
* Note: This does not affect values in EEPROM until M500.
* M871: Probe Temperature Config
*
* Report / reset temperature compensation offsets.
* NOTE: This does not affect values in EEPROM until M500.
*
* Usage:
* M871 [ R | B | P | E ]
*
* No Parameters - Print current offset values.
* Parameters:
* None Print current offset values
*
* Select only one of these flags:
* R - Reset all offsets to zero (i.e., disable compensation).
* B - Manually set offset for bed
* P - Manually set offset for probe
* E - Manually set offset for extruder
* Select only one of these flags:
* R Reset all offsets to zero (i.e., disable compensation)
* B Manually set offset for bed
* P Manually set offset for probe
* E Manually set offset for extruder
*
* With B, P, or E:
* I[index] - Index in the array
* V[value] - Adjustment in µm
* With B, P, or E:
* I<index> Index in the array
* V<value> Adjustment in µm
*/
void GcodeSuite::M871() {

View file

@ -31,32 +31,32 @@
#include "../../MarlinCore.h" // for idle()
/**
* M100 Free Memory Watcher
* M100: Free Memory Watcher
*
* This code watches the free memory block between the bottom of the heap and the top of the stack.
* This memory block is initialized and watched via the M100 command.
*
* M100 I Initializes the free memory block and prints vitals statistics about the area
* Parameters:
* I Initializes the free memory block and prints vitals statistics about the area
*
* M100 F Identifies how much of the free memory block remains free and unused. It also
* detects and reports any corruption within the free memory block that may have
* happened due to errant firmware.
* F Identifies how much of the free memory block remains free and unused. It also
* detects and reports any corruption within the free memory block that may have
* happened due to errant firmware.
*
* M100 D Does a hex display of the free memory block along with a flag for any errant
* data that does not match the expected value.
* D Does a hex display of the free memory block along with a flag for any errant
* data that does not match the expected value.
*
* M100 C x Corrupts x locations within the free memory block. This is useful to check the
* correctness of the M100 F and M100 D commands.
* C x Corrupts x locations within the free memory block. This is useful to check the
* correctness of the M100 F and M100 D commands.
*
* Also, there are two support functions that can be called from a developer's C code.
*
* uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start);
* void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size);
* uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start);
* void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size);
*
* Initial version by Roxy-3D
*/
#define M100_FREE_MEMORY_DUMPER // Enable for the `M100 D` Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Enable for the `M100 C` Corrupt sub-command
#define M100_FREE_MEMORY_DUMPER // Enable for the 'M100 D' Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Enable for the 'M100 C' Corrupt sub-command
#define TEST_BYTE ((char) 0xE5)

View file

@ -39,7 +39,15 @@
#if ENABLED(DELTA)
/**
* M666: Set delta endstop adjustment
* M666: Set Delta endstop adjustments
*
* Adjust the endstop offsets on a Delta printer.
*
* Parameters:
* None Report current offsets
* X<intint> Adjustment for the X actuator endstop
* Y<intint> Adjustment for the Y actuator endstop
* Z<int> Adjustment for the Z actuator endstop
*/
void GcodeSuite::M666() {
DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING));
@ -74,14 +82,22 @@
#else
/**
* M666: Set Dual Endstops offsets for X, Y, and/or Z.
* With no parameters report current offsets.
* M666: Set Dual Endstop Offsets
*
* For Triple / Quad Z Endstops:
* Set Z2 Only: M666 S2 Z<offset>
* Set Z3 Only: M666 S3 Z<offset>
* Set Z4 Only: M666 S4 Z<offset>
* Set All: M666 Z<offset>
* Adjust the offsets for dual (or multiple) endstops.
*
* Parameters:
* None Report current offsets
* X<int> Offset for the X axis endstops
* Y<int> Offset for the Y axis endstops
* Z<int> Offset for the Z axis endstops
*
* Example:
* For Triple / Quad Z Endstops:
* M666 S2 Z<offset> ; Set Z2 Only
* M666 S3 Z<offset> ; Set Z3 Only
* M666 S4 Z<offset> ; Set Z4 Only
* M666 Z<offset> ; Set All
*/
void GcodeSuite::M666() {
if (!parser.seen_any()) return M666_report();

View file

@ -28,12 +28,16 @@
#include "../../module/planner.h"
/**
* M852: Get or set the machine skew factors. Reports current values with no arguments.
* M852: Bed Skew Compensation
*
* S[xy_factor] - Alias for 'I'
* I[xy_factor] - New XY skew factor
* J[xz_factor] - New XZ skew factor
* K[yz_factor] - New YZ skew factor
* Get or set the machine skew factors; correct for misalignment
*
* Parameters:
* None Report current values
* S<xy_factor> Alias for 'I'
* I<xy_factor> New XY skew factor
* J<xz_factor> New XZ skew factor
* K<yz_factor> New YZ skew factor
*/
void GcodeSuite::M852() {
if (!parser.seen("SIJK")) return M852_report();

View file

@ -24,16 +24,15 @@
#include "../../module/motion.h"
/**
* M220: Set speed percentage factor, aka "Feed Rate"
* M220: Set Feedrate Percentage
*
* Parameters
* S<percent> : Set the feed rate percentage factor
* Parameters:
* None Report the current speed percentage factor
* S<percent> Set the feed rate percentage factor
*
* Report the current speed percentage factor if no parameter is specified
*
* For MMU2 and MMU2S devices...
* B : Flag to back up the current factor
* R : Flag to restore the last-saved factor
* For MMU2 and MMU2S devices:
* B<flag> Back up the current factor
* R<flag> Restore the last-saved factor
*/
void GcodeSuite::M220() {
if (!parser.seen_any()) {

View file

@ -28,22 +28,22 @@
#include "../../module/temperature.h"
/**
* M301: Set PID parameters P I D (and optionally C, L)
* M301: Set Hotend PID
*
* E[extruder] Default: 0
* Set PID parameters P I D (and optionally C, L)
*
* P[float] Kp term
* I[float] Ki term (unscaled)
* D[float] Kd term (unscaled)
* Parameters:
* E<extruder> Default: 0
* P<float> Kp term
* I<float> Ki term (unscaled)
* D<float> Kd term (unscaled)
*
* With PID_EXTRUSION_SCALING:
* With PID_EXTRUSION_SCALING:
* C<float> Kc term
* L<int> LPQ length
*
* C[float] Kc term
* L[int] LPQ length
*
* With PID_FAN_SCALING:
*
* F[float] Kf term
* With PID_FAN_SCALING:
* F<float> Kf term
*/
void GcodeSuite::M301() {
// multi-extruder PID patch: M301 updates or prints a single extruder's PID values

View file

@ -46,15 +46,16 @@ void protected_pin_err() {
/**
* M42: Change pin status via G-Code
*
* P<pin> Pin number (LED if omitted)
* For LPC1768 specify pin P1_02 as M42 P102,
* P1_20 as M42 P120, etc.
* Parameters:
* P<pin> Pin number (LED if omitted)
* For LPC1768 specify pin P1_02 as M42 P102,
* P1_20 as M42 P120, etc.
*
* S<byte> Pin status from 0 - 255
* I Flag to ignore Marlin's pin protection
* S<byte> Pin status from 0-255
* I Flag to ignore Marlin's pin protection
*
* T<mode> Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN
* 4=INPUT_ANALOG 5=OUTPUT_OPEN_DRAIN
* T<mode> Pin mode: 0=INPUT | 1=OUTPUT | 2=INPUT_PULLUP | 3=INPUT_PULLDOWN
* 4=INPUT_ANALOG | 5=OUTPUT_OPEN_DRAIN
*/
void GcodeSuite::M42() {
const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN));

View file

@ -155,13 +155,16 @@
#elif ENABLED(MULTI_NOZZLE_DUPLICATION)
/**
* M605: Set multi-nozzle duplication mode
* M605: Multi Nozzle Mode
*
* S2 - Enable duplication mode
* P[mask] - Bit-mask of nozzles to include in the duplication set.
* A value of 0 disables duplication.
* E[index] - Last nozzle index to include in the duplication set.
* A value of 0 disables duplication.
* Set multi-nozzle duplication mode.
*
* Parameters:
* S2 Enable duplication mode
* P<mask> Bit-mask of nozzles to include in the duplication set
* A value of 0 disables duplication
* E<index> Last nozzle index to include in the duplication set
* A value of 0 disables duplication
*/
void GcodeSuite::M605() {
bool ena = false;

View file

@ -43,14 +43,15 @@
/**
* T0-T<n>: Switch tool, usually switching extruders
*
* F[units/min] Set the movement feedrate
* S1 Don't move the tool in XY after change
* Parameters:
* F<units/min> Set the movement feedrate
* S1 Don't move the tool in XY after change
*
* For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S)
* T[n] G-code to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels.
* T? G-code to extrude shouldn't have to follow. Load to extruder wheels is done automatically.
* Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load.
* Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated.
* For PRUSA_MMU2(S) and EXTENDABLE_EMU_MMU2(S)
* T<n> G-code to extrude at least 38.10 mm at feedrate 19.02 mm/s must follow immediately to load to extruder wheels.
* T? G-code to extrude shouldn't have to follow. Load to extruder wheels is done automatically.
* Tx Same as T?, but nozzle doesn't have to be preheated. Tc requires a preheated nozzle to finish filament load.
* Tc Load to nozzle after filament was prepared by Tc and nozzle is already heated.
*/
void GcodeSuite::T(const int8_t tool_index) {

View file

@ -28,12 +28,15 @@
#include "../../../feature/mixing.h"
/**
* M163: Set a single mix factor for a mixing extruder
* This is called "weight" by some systems.
* Must be followed by M164 to normalize and commit them.
* M163: Set Mix Factor
*
* S[index] The channel index to set
* P[float] The mix value
* Set a single mix factor for a mixing extruder
* This is called "weight" by some systems.
* Must be followed by M164 to normalize and commit them.
*
* Parameters:
* S<index> The channel index to set
* P<float> The mix value
*/
void GcodeSuite::M163() {
const int mix_index = parser.intval('S');
@ -42,10 +45,13 @@ void GcodeSuite::M163() {
}
/**
* M164: Normalize and commit the mix.
* M164: Save Mix
*
* S[index] The virtual tool to store
* If 'S' is omitted update the active virtual tool.
* Normalize and commit the mix.
*
* Parameters:
* S<index> The virtual tool to store
* If 'S' is omitted update the active virtual tool.
*/
void GcodeSuite::M164() {
#if MIXING_VIRTUAL_TOOLS > 1
@ -64,16 +70,19 @@ void GcodeSuite::M164() {
#if ENABLED(DIRECT_MIXING_IN_G1)
/**
* M165: Set multiple mix factors for a mixing extruder.
* Omitted factors will be set to 0.
* The mix is normalized and stored in the current virtual tool.
* M165: Set Mix
*
* A[factor] Mix factor for extruder stepper 1
* B[factor] Mix factor for extruder stepper 2
* C[factor] Mix factor for extruder stepper 3
* D[factor] Mix factor for extruder stepper 4
* H[factor] Mix factor for extruder stepper 5
* I[factor] Mix factor for extruder stepper 6
* Set multiple mix factors for a mixing extruder.
* Omitted factors will be set to 0.
* The mix is normalized and stored in the current virtual tool.
*
* Parameters:
* A<factor> Mix factor for extruder stepper 1
* B<factor> Mix factor for extruder stepper 2
* C<factor> Mix factor for extruder stepper 3
* D<factor> Mix factor for extruder stepper 4
* H<factor> Mix factor for extruder stepper 5
* I<factor> Mix factor for extruder stepper 6
*/
void GcodeSuite::M165() {
// Get mixing parameters from the G-Code

View file

@ -40,19 +40,23 @@ inline void echo_zt(const int t, const_float_t z) {
}
/**
* M166: Set a simple gradient mix for a two-component mixer
* based on the Geeetech A10M implementation by Jone Liu.
* M166: Gradient Mix
*
* S[bool] - Enable / disable gradients
* A[float] - Starting Z for the gradient
* Z[float] - Ending Z for the gradient. (Must be greater than the starting Z.)
* I[index] - V-Tool to use as the starting mix.
* J[index] - V-Tool to use as the ending mix.
* Set a simple gradient mix for a two-component mixer
* based on the Geeetech A10M implementation by Jone Liu.
*
* T[index] - A V-Tool index to use as an alias for the Gradient (Requires GRADIENT_VTOOL)
* T with no index clears the setting. Note: This can match the I or J value.
* Parameters:
* S<bool> Enable / disable gradients
* A<float> Starting Z for the gradient
* Z<float> Ending Z for the gradient. (Must be greater than the starting Z.)
* I<index> V-Tool to use as the starting mix
* J<index> V-Tool to use as the ending mix
* T<index> A V-Tool index to use as an alias for the Gradient (Requires GRADIENT_VTOOL)
* T T with no index clears the setting
* NOTE: This can match the I or J value.
*
* Example: M166 S1 A0 Z20 I0 J1
* Example:
* M166 S1 A0 Z20 I0 J1
*/
void GcodeSuite::M166() {
if (parser.seenval('A')) mixer.gradient.start_z = parser.value_float();

View file

@ -29,12 +29,15 @@
#include "../../gcode.h"
/**
* M430: Enable/disable current LCD display
* With no parameters report the system current draw (in Amps)
* M430: Power Monitor
*
* I[bool] - Set Display of current on the LCD
* V[bool] - Set Display of voltage on the LCD
* W[bool] - Set Display of power on the LCD
* Enable/disable power monitor on LCD display.
*
* Parameters:
* None Report the system current draw in Amps/Volts/Watts
* I<bool> Display current (A) on the LCD
* V<bool> Display voltage (V) on the LCD
* W<bool> Display power/watts (W) on the LCD
*/
void GcodeSuite::M430() {
bool do_report = true;

View file

@ -30,14 +30,17 @@
#include "../../../lcd/marlinui.h"
/**
* M413: Enable / Disable power-loss recovery
* M413: Power-loss Recovery
*
* Enable/Disable power-loss recovery
*
* Parameters
* S[bool] - Flag to enable / disable.
* If omitted, report current state.
* None Report power-loss recovery state
* S<bool> Flag to enable/disable
* If omitted, report current state.
*
* With PLR_BED_THRESHOLD:
* B Bed Temperature above which recovery will proceed without asking permission.
* B<temp> Bed Temperature above which recovery will proceed without asking permission.
*/
void GcodeSuite::M413() {

View file

@ -49,59 +49,57 @@ static void gcodes_M704_M705_M706(uint16_t gcode) {
}
/**
* ### M704 - Preload to MMU
* #### Usage
* M704: Preload to MMU
*
* Usage:
* M704 [ P ]
*
* #### Parameters
* - `P` - n index of slot (zero based, so 0-4 like T0 and T4)
* Parameters:
* P<index> Index of slot (zero based, 0-4, i.e., T0 and T4)
*/
void GcodeSuite::M704() {
gcodes_M704_M705_M706(704);
}
/**
* ### M705 - Eject filament
* #### Usage
* M705: Eject Filament
*
* Usage:
* M705 [ P ]
*
* #### Parameters
* - `P` - n index of slot (zero based, so 0-4 like T0 and T4)
* Parameters:
* P<index> Index of slot (zero based, 0-4, i.e., T0 and T4)
*/
void GcodeSuite::M705() {
gcodes_M704_M705_M706(705);
}
/*!
* ### M706 - Cut filament
* #### Usage
/**
* M706: Cut Filament
*
* Usage:
* M706 [ P ]
*
* #### Parameters
* - `P` - n index of slot (zero based, so 0-4 like T0 and T4)
* Parameters:
* P<index> Index of slot (zero based, 0-4, i.e., T0 and T4)
*/
void GcodeSuite::M706() {
gcodes_M704_M705_M706(706);
}
/**
* ### M707 - Read from MMU register
* #### Usage
* M707: Read from MMU Register
*
* Usage:
* M707 [ A ]
*
* #### Parameters
* - `A` - Address of register in hexidecimal.
* Parameters:
* A<hex> Address of register in hexidecimal
*
* #### Example
*
* M707 A0x1b - Read a 8bit integer from register 0x1b and prints the result onto the serial line.
* Example:
* M707 A0x1b - Read a 8bit integer from register 0x1b and prints the result onto the serial line.
*
* Does nothing if the A parameter is not present or if MMU is not enabled.
*
*/
void GcodeSuite::M707() {
if (mmu3.enabled() && parser.seenval('A')) {
@ -111,17 +109,17 @@ void GcodeSuite::M707() {
}
/**
* ### M708 - Write to MMU register
* #### Usage
* M708: Write to MMU Register
*
* Usage:
* M708 [ A | X ]
*
* #### Parameters
* - `A` - Address of register in hexidecimal.
* - `X` - Data to write (16-bit integer). Default value 0.
* Parameters:
* A<hex> Address of register in hexidecimal
* X<int> Data to write (16-bit integer). Default value 0
*
* #### Example
* M708 A0x1b X05 - Write to register 0x1b the value 05.
* Example:
* M708 A0x1b X05 - Write to register 0x1b the value 05.
*
* Does nothing if A parameter is missing or if MMU is not enabled.
*/
@ -137,27 +135,26 @@ void GcodeSuite::M708() {
}
/**
* ### M709 - MMU power & reset
* The MK3S cannot not power off the MMU, but we can en- and disable the MMU.
* M709: MMU Power & Reset
*
* The MK3S cannot not power off the MMU, but we can enable/disable the MMU.
* The new state of the MMU is stored in printer's EEPROM.
* i.e., If you disable the MMU via M709, it will not be activated after the printer resets.
* Usage
* (i.e., If you disable the MMU via M709, it will not be activated after the printer resets.)
*
* Usage:
* M709 [ S | X ]
*
* Parameters
* - `X` - Reset MMU (0:soft reset | 1:hardware reset | 42: erase MMU eeprom)
* - `S` - En-/disable the MMU (0:off | 1:on)
* Parameters:
* X<int> Reset MMU (0:soft reset | 1:hardware reset | 42: erase MMU eeprom)
* S<bool> Enable/Disable the MMU (1=ON | 0=OFF)
*
* Examples
*
* M709 X0 ; issue an X0 command via communication into the MMU (soft reset)
* M709 X1 ; toggle the MMU's reset pin (hardware reset)
* M709 X42 ; erase MMU EEPROM
* M709 S1 ; enable MMU
* M709 S0 ; disable MMU
* M709 ; Serial message if en- or disabled
* Examples:
* M709 X0 ; Issue an X0 command via communication into the MMU (soft reset)
* M709 X1 ; Toggle the MMU's reset pin (hardware reset)
* M709 X42 ; Erase MMU EEPROM
* M709 S1 ; Enable MMU
* M709 S0 ; Disable MMU
* M709 ; Serial message if enabled/disabled
*/
void GcodeSuite::M709() {
if (parser.seenval('S')) {

View file

@ -65,7 +65,7 @@
* G38 - Probe in any direction using the Z_MIN_PROBE (Requires G38_PROBE_TARGET)
* G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL)
* G60 - Save current position. (Requires SAVED_POSITIONS)
* G61 - Apply/restore saved coordinates. (Requires SAVED_POSITIONS)
* G61 - Apply/Restore saved coordinates. (Requires SAVED_POSITIONS)
* G76 - Calibrate first layer temperature offsets. (Requires PTC_PROBE and PTC_BED)
* G80 - Cancel current motion mode (Requires GCODE_MOTION_MODES)
* G90 - Use Absolute Coordinates
@ -91,12 +91,12 @@
*
*** Print from Media (SDSUPPORT) ***
* M20 - List SD card. (Requires SDSUPPORT)
* M21 - Init SD card. (Requires SDSUPPORT) With MULTI_VOLUME select a drive with `M21 Pn` / 'M21 S' / 'M21 U'.
* M21 - Init SD card. (Requires SDSUPPORT) With MULTI_VOLUME select a drive with 'M21 Pn' / 'M21 S' / 'M21 U'.
* M22 - Release SD card. (Requires SDSUPPORT)
* M23 - Select SD file: "M23 /path/file.gco". (Requires SDSUPPORT)
* M24 - Start/resume SD print. (Requires SDSUPPORT)
* M24 - Start/Resume SD print. (Requires SDSUPPORT)
* M25 - Pause SD print. (Requires SDSUPPORT)
* M26 - Set SD position in bytes: "M26 S12345". (Requires SDSUPPORT)
* M26 - Set SD position in bytes: 'M26 S12345'. (Requires SDSUPPORT)
* M27 - Report SD print status. (Requires SDSUPPORT)
* OR, with 'S<seconds>' set the SD status auto-report interval. (Requires AUTO_REPORT_SD_STATUS)
* OR, with 'C' get the current filename.
@ -104,8 +104,8 @@
* M29 - Stop SD write. (Requires SDSUPPORT)
* M30 - Delete file from SD: "M30 /path/file.gco" (Requires SDSUPPORT)
* M31 - Report time since last M109 or SD card start to serial.
* M32 - Select file and start SD print: "M32 [S<bytepos>] !/path/file.gco#". (Requires SDSUPPORT)
* Use P to run other files as sub-programs: "M32 P !filename#"
* M32 - Select file and start SD print: 'M32 [S<bytepos>] !/path/file.gco#'. (Requires SDSUPPORT)
* Use P to run other files as sub-programs: 'M32 P !filename#'
* The '#' is necessary when calling from within sd files, as it stops buffer prereading
* M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT)
* M34 - Set SD Card sorting options. (Requires SDCARD_SORT_ALPHA)
@ -145,11 +145,11 @@
* R<temp> Wait for extruder current temp to reach target temp. ** Wait for heating or cooling. **
* If AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
*
* M110 - Get or set the current line number. (Used by host printing)
* M111 - Set debug flags: "M111 S<flagbits>". See flag bits defined in enum.h.
* M110 - Set / Report the current line number. (Used by host printing)
* M111 - Set debug flags: 'M111 S<flagbits>'. See flag bits defined in enum.h.
* M112 - Full Shutdown.
*
* M113 - Get or set the timeout interval for Host Keepalive "busy" messages. (Requires HOST_KEEPALIVE_FEATURE)
* M113 - Set / Report the timeout interval for Host Keepalive "busy" messages. (Requires HOST_KEEPALIVE_FEATURE)
* M114 - Report current position.
* M115 - Report capabilities. (Requires CAPABILITIES_REPORT)
* M117 - Display a message on the controller screen. (Requires an LCD)
@ -184,9 +184,9 @@
* M192 - Wait for probe to reach target temperature. (Requires TEMP_SENSOR_PROBE)
* M193 - R<temp> Wait for cooler to reach target temp. ** Wait for cooling. **
* M200 - Set filament diameter, D<diameter>, setting E axis units to cubic. (Use S0 to revert to linear units.)
* M201 - Set max acceleration in units/s^2 for print moves: "M201 X<accel> Y<accel> Z<accel> E<accel>"
* M202 - Set max acceleration in units/s^2 for travel moves: "M202 X<accel> Y<accel> Z<accel> E<accel>" ** UNUSED IN MARLIN! **
* M203 - Set maximum feedrate: "M203 X<fr> Y<fr> Z<fr> E<fr>" in units/sec.
* M201 - Set max acceleration in units/s^2 for print moves: 'M201 X<accel> Y<accel> Z<accel> E<accel>'
* M202 - Set max acceleration in units/s^2 for travel moves: 'M202 X<accel> Y<accel> Z<accel> E<accel>' ** UNUSED IN MARLIN! **
* M203 - Set maximum feedrate: 'M203 X<fr> Y<fr> Z<fr> E<fr>' in units/sec.
* M204 - Set default acceleration in units/sec^2: P<printing> R<extruder_only> T<travel>
* M205 - Set advanced settings. Current units apply:
S<print> T<travel> minimum speeds
@ -197,23 +197,23 @@
* M208 - Set Recover (unretract) Additional (!) Length: S<length> and Feedrate: F<units/min>. (Requires FWRETRACT)
* M209 - Turn Automatic Retract Detection on/off: S<0|1> (For slicers that don't support G10/11). (Requires FWRETRACT_AUTORETRACT)
Every normal extrude-only move will be classified as retract depending on the direction.
* M210 - Set or Report the homing feedrate (Requires EDITABLE_HOMING_FEEDRATE)
* M210 - Set / Report the homing feedrate (Requires EDITABLE_HOMING_FEEDRATE)
* M211 - Enable, Disable, and/or Report software endstops: S<0|1> (Requires MIN_SOFTWARE_ENDSTOPS or MAX_SOFTWARE_ENDSTOPS)
* M217 - Set filament swap parameters: "M217 S<length> P<feedrate> R<feedrate>". (Requires SINGLENOZZLE)
* M218 - Set/get a tool offset: "M218 T<index> X<offset> Y<offset>". (Requires 2 or more extruders)
* M220 - Set Feedrate Percentage: "M220 S<percent>" (i.e., "FR" on the LCD)
* Use "M220 B" to back up the Feedrate Percentage and "M220 R" to restore it. (Requires an MMU_MODEL version 2 or 2S)
* M221 - Set Flow Percentage: "M221 S<percent>" (Requires an extruder)
* M226 - Wait until a pin is in a given state: "M226 P<pin> S<state>" (Requires DIRECT_PIN_CONTROL)
* M217 - Set filament swap parameters: 'M217 S<length> P<feedrate> R<feedrate>'. (Requires SINGLENOZZLE)
* M218 - Set / Report a tool offset: 'M218 T<index> X<offset> Y<offset>'. (Requires 2 or more extruders)
* M220 - Set Feedrate Percentage: 'M220 S<percent>' (i.e., "FR" on the LCD)
* Use 'M220 B' to back up the Feedrate Percentage and 'M220 R' to restore it. (Requires an MMU_MODEL version 2 or 2S)
* M221 - Set Flow Percentage: 'M221 S<percent>' (Requires an extruder)
* M226 - Wait until a pin is in a given state: 'M226 P<pin> S<state>' (Requires DIRECT_PIN_CONTROL)
* M240 - Trigger a camera to take a photograph. (Requires PHOTO_GCODE)
* M250 - Set LCD contrast: "M250 C<contrast>" (0-63). (Requires LCD support)
* M255 - Set LCD sleep time: "M255 S<minutes>" (0-99). (Requires an LCD with brightness or sleep/wake)
* M256 - Set LCD brightness: "M256 B<brightness>" (0-255). (Requires an LCD with brightness control)
* M250 - Set LCD contrast: 'M250 C<contrast>' (0-63). (Requires LCD support)
* M255 - Set LCD sleep time: 'M255 S<minutes>' (0-99). (Requires an LCD with brightness or sleep/wake)
* M256 - Set LCD brightness: 'M256 B<brightness>' (0-255). (Requires an LCD with brightness control)
* M260 - i2c Send Data (Requires EXPERIMENTAL_I2CBUS)
* M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS)
* M280 - Set servo position absolute: "M280 P<index> S<angle|µs>". (Requires servos)
* M281 - Set servo min|max position: "M281 P<index> L<min> U<max>". (Requires EDITABLE_SERVO_ANGLES)
* M282 - Detach servo: "M282 P<index>". (Requires SERVO_DETACH_GCODE)
* M280 - Set servo position absolute: 'M280 P<index> S<angle|µs>'. (Requires servos)
* M281 - Set servo min|max position: 'M281 P<index> L<min> U<max>'. (Requires EDITABLE_SERVO_ANGLES)
* M282 - Detach servo: 'M282 P<index>'. (Requires SERVO_DETACH_GCODE)
* M290 - Babystepping (Requires BABYSTEPPING)
* M293 - Babystep Z UP (Requires EP_BABYSTEPPING)
* M294 - Babystep Z DOWN (Requires EP_BABYSTEPPING)
@ -234,13 +234,13 @@
* M401 - Deploy and activate Z probe. (Requires a probe)
* M402 - Deactivate and stow Z probe. (Requires a probe)
* M403 - Set filament type for PRUSA MMU2
* M404 - Display or set the Nominal Filament Width: "W<diameter>". (Requires FILAMENT_WIDTH_SENSOR)
* M405 - Enable Filament Sensor flow control. "M405 D<delay_cm>". (Requires FILAMENT_WIDTH_SENSOR)
* M404 - Set / Report the Nominal Filament Width: 'W<diameter>'. (Requires FILAMENT_WIDTH_SENSOR)
* M405 - Enable Filament Sensor flow control. 'M405 D<delay_cm>'. (Requires FILAMENT_WIDTH_SENSOR)
* M406 - Disable Filament Sensor flow control. (Requires FILAMENT_WIDTH_SENSOR)
* M407 - Display measured filament diameter in millimeters. (Requires FILAMENT_WIDTH_SENSOR)
* M410 - Quickstop. Abort all planned moves.
* M412 - Enable / Disable Filament Runout Detection. (Requires FILAMENT_RUNOUT_SENSOR)
* M413 - Enable / Disable Power-Loss Recovery. (Requires POWER_LOSS_RECOVERY)
* M412 - Enable/Disable Filament Runout Detection. (Requires FILAMENT_RUNOUT_SENSOR)
* M413 - Enable/Disable Power-Loss Recovery. (Requires POWER_LOSS_RECOVERY)
* M414 - Set language by index. (Requires LCD_LANGUAGE_2...)
* M420 - Enable/Disable Leveling (with current values) S1=enable S0=disable (Requires MESH_BED_LEVELING or ABL)
* M421 - Set a single Z coordinate in the Mesh Leveling grid. X<units> Y<units> Z<units> (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL)
@ -250,32 +250,32 @@
* M430 - Read the system current, voltage, and power (Requires POWER_MONITOR_CURRENT, POWER_MONITOR_VOLTAGE, or POWER_MONITOR_FIXED_VOLTAGE)
* M485 - Send RS485 packets (Requires RS485_SERIAL_PORT)
* M486 - Identify and cancel objects. (Requires CANCEL_OBJECTS)
* M493 - Get or set input FT Motion / Shaping parameters. (Requires FT_MOTION)
* M493 - Set / Report input FT Motion/Shaping parameters. (Requires FT_MOTION)
* M500 - Store parameters in EEPROM. (Requires EEPROM_SETTINGS)
* M501 - Restore parameters from EEPROM. (Requires EEPROM_SETTINGS)
* M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! **
* M503 - Print the current settings (in memory): "M503 S<verbose>". S0 specifies compact output.
* M503 - Print the current settings (in memory): 'M503 S<verbose>'. S0 specifies compact output.
* M504 - Validate EEPROM contents. (Requires EEPROM_SETTINGS)
* M510 - Lock Printer (Requires PASSWORD_FEATURE)
* M511 - Unlock Printer (Requires PASSWORD_UNLOCK_GCODE)
* M512 - Set/Change/Remove Password (Requires PASSWORD_CHANGE_GCODE)
* M524 - Abort the current SD print job started with M24. (Requires SDSUPPORT)
* M540 - Enable/disable SD card abort on endstop hit: "M540 S<state>". (Requires SD_ABORT_ON_ENDSTOP_HIT)
* M550 - Set the machine name: "M550 P<name>". (Requires CONFIGURABLE_MACHINE_NAME)
* M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port)
* M553 - Get or set IP netmask. (Requires enabled Ethernet port)
* M554 - Get or set IP gateway. (Requires enabled Ethernet port)
* M540 - Enable/Disable SD card abort on endstop hit: 'M540 S<state>'. (Requires SD_ABORT_ON_ENDSTOP_HIT)
* M550 - Set the machine name: 'M550 P<name>'. (Requires CONFIGURABLE_MACHINE_NAME)
* M552 - Set / Report IP address. Enable/Disable network interface. (Requires enabled Ethernet port)
* M553 - Set / Report IP netmask. (Requires enabled Ethernet port)
* M554 - Set / Report IP gateway. (Requires enabled Ethernet port)
* M569 - Enable stealthChop on an axis. (Requires *_DRIVER_TYPE TMC(2130|2160|2208|2209|2240|5130|5160))
* M575 - Change the serial baud rate. (Requires BAUD_RATE_GCODE)
* M592 - Get or set Nonlinear Extrusion parameters. (Requires NONLINEAR_EXTRUSION)
* M593 - Get or set input shaping parameters. (Requires INPUT_SHAPING_[XY])
* M600 - Pause for filament change: "M600 X<pos> Y<pos> Z<raise> E<first_retract> L<later_retract>". (Requires ADVANCED_PAUSE_FEATURE)
* M603 - Configure filament change: "M603 T<tool> U<unload_length> L<load_length>". (Requires ADVANCED_PAUSE_FEATURE)
* M605 - Set Dual X-Carriage movement mode: "M605 S<mode> [X<x_offset>] [R<temp_offset>]". (Requires DUAL_X_CARRIAGE)
* M665 - Set delta configurations: "M665 H<delta height> L<diagonal rod> R<delta radius> S<segments/s> B<calibration radius> X<Alpha angle trim> Y<Beta angle trim> Z<Gamma angle trim> (Requires DELTA)
* Set SCARA configurations: "M665 S<segments-per-second> P<theta-psi-offset> T<theta-offset> Z<z-offset> (Requires MORGAN_SCARA or MP_SCARA)
* Set Polargraph draw area and belt length: "M665 S<segments-per-second> L<draw-area-left> R<draw-area-right> T<draw-area-top> B<draw-area-bottom> H<max-belt-length>"
* M666 - Set/get offsets for delta (Requires DELTA) or dual endstops. (Requires [XYZ]_DUAL_ENDSTOPS)
* M592 - Set / Report Nonlinear Extrusion parameters. (Requires NONLINEAR_EXTRUSION)
* M593 - Set / Report input shaping parameters. (Requires INPUT_SHAPING_[XY])
* M600 - Pause for filament change: 'M600 X<pos> Y<pos> Z<raise> E<first_retract> L<later_retract>'. (Requires ADVANCED_PAUSE_FEATURE)
* M603 - Configure filament change: 'M603 T<tool> U<unload_length> L<load_length>'. (Requires ADVANCED_PAUSE_FEATURE)
* M605 - Set Dual X-Carriage movement mode: 'M605 S<mode> [X<x_offset>] [R<temp_offset>]'. (Requires DUAL_X_CARRIAGE)
* M665 - Set Delta configurations: 'M665 H<delta height> L<diagonal rod> R<delta radius> S<segments/s> B<calibration radius> X<Alpha angle trim> Y<Beta angle trim> Z<Gamma angle trim>' (Requires DELTA)
* Set SCARA configurations: 'M665 S<segments-per-second> P<theta-psi-offset> T<theta-offset> Z<z-offset>' (Requires MORGAN_SCARA or MP_SCARA)
* Set Polargraph draw area and belt length: 'M665 S<segments-per-second> L<draw-area-left> R<draw-area-right> T<draw-area-top> B<draw-area-bottom> H<max-belt-length>'
* M666 - Set / Report offsets for delta (Requires DELTA) or dual endstops. (Requires [XYZ]_DUAL_ENDSTOPS)
* M672 - Set/Reset Duet Smart Effector's sensitivity. (Requires DUET_SMART_EFFECTOR and SMART_EFFECTOR_MOD_PIN)
* M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES)
* M702 - Unload filament (Requires FILAMENT_LOAD_UNLOAD_GCODES)
@ -289,10 +289,10 @@
* M709 - MMU power & reset
*
* M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS)
* M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS)
* M810-M819 - Define/Execute a G-code macro (Requires GCODE_MACROS)
* M820 - Report all defined M810-M819 G-code macros (Requires GCODE_MACROS)
* M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below)
* M852 - Set skew factors: "M852 [I<xy>] [J<xz>] [K<yz>]". (Requires SKEW_CORRECTION_GCODE, plus SKEW_CORRECTION_FOR_Z for IJ)
* M852 - Set skew factors: 'M852 I<xy> J<xz> K<yz>'. (Requires SKEW_CORRECTION_GCODE, plus SKEW_CORRECTION_FOR_Z for IJ)
*
*** I2C_POSITION_ENCODERS ***
* M860 - Report the position of position encoder modules.
@ -301,15 +301,15 @@
* M863 - Perform steps-per-mm calibration for position encoder modules.
* M864 - Change position encoder module I2C address.
* M865 - Check position encoder module firmware version.
* M866 - Report or reset position encoder module error count.
* M867 - Enable/disable or toggle error correction for position encoder modules.
* M868 - Report or set position encoder module error correction threshold.
* M866 - Report/Reset position encoder module error count.
* M867 - Enable/Disable or toggle error correction for position encoder modules.
* M868 - Set / Report position encoder module error correction threshold.
* M869 - Report position encoder module error.
*
* M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND)
* M871 - Print/Reset/Clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND)
* M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER)
* M900 - Set or Report Linear Advance K-factor. (Requires LIN_ADVANCE)
* M906 - Set or Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660))
* M900 - Set / Report Linear Advance K-factor. (Requires LIN_ADVANCE)
* M906 - Set / Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660))
* M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots)
* M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN)
* M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC)
@ -318,7 +318,7 @@
* M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660))
* M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD)
* M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING)
* M919 - Set or Report motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc.
* M919 - Set / Report motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc.
* If no parameters are given, report. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660))
* M920 - Set Homing Current. (Requires distinct *_CURRENT_HOME settings)
* M936 - OTA update firmware. (Requires OTA_FIRMWARE_UPDATE)
@ -342,12 +342,12 @@
* M997 - Perform in-application firmware update
* M999 - Restart after being stopped by error
*
* D... - Custom Development G-code. Add hooks to 'gcode_D.cpp' for developers to test features. (Requires MARLIN_DEV_MODE)
* D... - Custom Development G-code. Add hooks to "gcode_D.cpp" for developers to test features. (Requires MARLIN_DEV_MODE)
* D576 - Set buffer monitoring options. (Requires BUFFER_MONITORING)
*
*** "T" Codes ***
*
* T0-T3 - Select an extruder (tool) by index: "T<n> F<units/min>"
* T0-T3 - Select an extruder (tool) by index: 'T<n> F<units/min>'
*/
#include "../inc/MarlinConfig.h"

View file

@ -29,7 +29,9 @@
/**
* M113: Get or set Host Keepalive interval (0 to disable)
*
* S<seconds> Optional. Set the keepalive interval.
* Parameters:
* None Report current keepalive interval
* S<seconds> Set the keepalive interval (0-60)
*/
void GcodeSuite::M113() {

View file

@ -69,7 +69,7 @@
#if IS_KINEMATIC
// Kinematics applied to the leveled position
SERIAL_ECHOPGM(TERN(POLAR, "Polar", TERN(IS_SCARA, "Scara", "Delta")) "K: " );
SERIAL_ECHOPGM(TERN(POLAR, "Polar", TERN(IS_SCARA, "SCARA", "Delta")) "K: " );
inverse_kinematics(leveled); // writes delta[]
report_linear_axis_pos(delta);
#endif
@ -92,7 +92,7 @@
#endif
SERIAL_ECHOPGM("FromStp:");
get_cartesian_from_steppers(); // writes 'cartes' (with forward kinematics)
get_cartesian_from_steppers(); // Writes 'cartes' (with forward kinematics)
xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(
planner.get_axis_position_mm(E_AXIS),
cartes.x, cartes.y, cartes.z,
@ -115,12 +115,18 @@
#endif // M114_DETAIL
/**
* M114: Report the current position to host.
* Since steppers are moving, the count positions are
* projected by using planner calculations.
* D - Report more detail. This syncs the planner. (Requires M114_DETAIL)
* E - Report E stepper position (Requires M114_DETAIL)
* R - Report the realtime position instead of projected.
* M114: Get Current Position
*
* Report the current tool position to the host.
* Since steppers are moving, the count positions are
* projected by using planner calculations.
*
* With M114_DETAIL:
* D - Report detailed information
* E - Report E stepper position
*
* With M114_REALTIME:
* R - Report real position information
*/
void GcodeSuite::M114() {

View file

@ -54,9 +54,11 @@
#endif
/**
* M115: Capabilities string and extended capabilities report
* If a capability is not reported, hosts should assume
* the capability is not present.
* M115: Firmware Info
*
* Capabilities string and extended capabilities report.
* If a capability is not reported, hosts should assume
* the capability is not present.
*
* NOTE: Always make sure to add new capabilities to the RepRap Wiki
* at https://reprap.org/wiki/Firmware_Capabilities_Protocol

View file

@ -30,7 +30,16 @@
#include "../../libs/numtostr.h"
/**
* M73: Set percentage complete (for display on LCD)
* M73: Set Print Progress
*
* Set next interaction countdown, current print progress
* percentage, and/or remaining time for display on the LCD.
*
* Parameters:
* None Report current values
* C<minutes> Set next interaction countdown
* P<percent> Set current print progress percentage (0-100)
* R<minutes> Set remaining time
*
* Example:
* M73 P25.63 ; Set progress to 25.63%

View file

@ -232,7 +232,7 @@ void GCodeQueue::enqueue_now_P(PGM_P const pgcode) {
* Send an "ok" message to the host, indicating
* that a command was successfully processed.
*
* If ADVANCED_OK is enabled also include:
* With ADVANCED_OK:
* N<int> Line number of the command, if any
* P<int> Planner space remaining
* B<int> Block queue space remaining

View file

@ -28,7 +28,9 @@
#include "../../sd/cardreader.h"
/**
* M20: List SD card to serial output in [name] [size] format.
* M20: List Media Files
*
* By default output in [name] [size] format.
*
* With CUSTOM_FIRMWARE_UPLOAD:
* F<bool> - List BIN files only, for use with firmware upload

View file

@ -28,7 +28,7 @@
#include "../../sd/cardreader.h"
/**
* M21: Init SD Card
* M21: Mount Media
*
* With MULTI_VOLUME:
* P0 or S - Change to the SD Card and mount it
@ -46,7 +46,7 @@ void GcodeSuite::M21() {
}
/**
* M22: Release SD Card
* M22: Release Media
*/
void GcodeSuite::M22() {
if (!card.isStillPrinting()) card.release();

View file

@ -29,9 +29,14 @@
#include "../../lcd/marlinui.h"
/**
* M23: Open a file
* M23: Select File
*
* The path is relative to the root directory
* Select a file on mounted media for printing or processing.
* Follow with M24 to run the selected file.
*
* Parameters:
* <filename> The filename of the file to open
* (The path is relative to the root directory)
*/
void GcodeSuite::M23() {
// Simplify3D includes the size, so zero out all spaces (#7227)

View file

@ -48,7 +48,12 @@
#include "../../MarlinCore.h" // for startOrResumeJob
/**
* M24: Start or Resume SD Print
* M24: Start or Resume Media Print
*
* Parameters:
* With POWER_LOSS_RECOVERY:
* S<pos> Position in file to resume from
* T<time> Elapsed time since start of print
*/
void GcodeSuite::M24() {
@ -86,11 +91,11 @@ void GcodeSuite::M24() {
}
/**
* M25: Pause SD Print
* M25: Pause Media Print
*
* With PARK_HEAD_ON_PAUSE:
* Invoke M125 to store the current position and move to the park
* position. M24 will move the head back before resuming the print.
* Invoke 'M125' to store the current position and move to the park
* position. 'M24' will move the head back before resuming the print.
*/
void GcodeSuite::M25() {

View file

@ -28,7 +28,12 @@
#include "../../sd/cardreader.h"
/**
* M26: Set SD Card file index
* M26: Set Media File current index
*
* Set the next read position for the open file.
*
* Parameters:
* S<pos> Next file read position to set
*/
void GcodeSuite::M26() {
if (card.isMounted() && parser.seenval('S'))

View file

@ -29,8 +29,13 @@
/**
* M27: Get SD Card status
* OR, with 'S<seconds>' set the SD status auto-report interval. (Requires AUTO_REPORT_SD_STATUS)
* OR, with 'C' get the current filename.
*
* Parameters:
* None Report the current SD read position
* C Report the filename and long filename of the current file
*
* With AUTO_REPORT_SD_STATUS:
* S<seconds> Interval between auto-reports. S0 to disable
*/
void GcodeSuite::M27() {
if (parser.seen_test('C')) {

View file

@ -33,6 +33,12 @@
/**
* M28: Start SD Write
*
* Parameters:
* <filename> File name to write
*
* With BINARY_FILE_TRANSFER:
* B1 Set an optimized binary file transfer mode
*/
void GcodeSuite::M28() {

View file

@ -28,7 +28,10 @@
#include "../../sd/cardreader.h"
/**
* M30 <filename>: Delete SD Card file
* M30: Delete Media File
*
* Parameters:
* <filename> The filename of the file to delete
*/
void GcodeSuite::M30() {
if (card.isMounted()) {

View file

@ -28,7 +28,9 @@
#include "../../sd/cardreader.h"
/**
* M33: Get the long full path of a file or folder
* M33: Get Long Path
*
* Get the long full path of a file or folder
*
* Parameters:
* <dospath> Case-insensitive DOS-style path to a file or folder

View file

@ -28,17 +28,22 @@
#include "../../sd/cardreader.h"
/**
* M34: Set SD Card Sorting Options
* M34: Media Sorting
*
* S - Default sorting (i.e., SDSORT_REVERSE)
* S-1 - Reverse alpha sorting
* S0 - FID Order (not always newest)
* S1 - Forward alpha sorting
* S2 - Alias for S-1 [deprecated]
* Set Media Sorting Options
*
* F-1 - Folders above files
* F0 - Sort According to 'S'
* F1 - Folders after files
* Parameters:
* S<inr> Sorting Order:
* S Default sorting (i.e., SDSORT_REVERSE)
* S-1 Reverse alpha sorting
* S0 FID Order (not always newest)
* S1 Forward alpha sorting
* S2 Alias for S-1 [deprecated]
*
* F<int> Folder Sorting:
* F-1 Folders before files
* F0 No folder sorting (Sort according to 'S')
* F1 Folders after files
*/
void GcodeSuite::M34() {
if (parser.seen('S')) card.setSortOn(SortFlag(parser.ushortval('S', TERN(SDSORT_REVERSE, AS_REV, AS_FWD))));

View file

@ -47,16 +47,16 @@
/**
* M106: Set Fan Speed
*
* I<index> Material Preset index (if material presets are defined)
* S<int> Speed between 0-255
* P<index> Fan index, if more than one fan
* Parameters:
* I<index> Material Preset index (if material presets are defined)
* S<int> Speed between 0-255
* P<index> Fan index, if more than one fan
*
* With EXTRA_FAN_SPEED enabled:
*
* T<int> Restore/Use/Set Temporary Speed:
* 1 = Restore previous speed after T2
* 2 = Use temporary speed set with T3-255
* 3-255 = Set the speed for use with T2
* With EXTRA_FAN_SPEED:
* T<int> Restore/Use/Set Temporary Speed:
* T1 Restore previous speed after T2
* T2 Use temporary speed set with T3-255
* T3-255 Set the speed for use with T2
*/
void GcodeSuite::M106() {
const uint8_t pfan = parser.byteval('P', _ALT_P);

View file

@ -64,9 +64,13 @@ void GcodeSuite::M306() {
case 2: tuning_type = Temperature::MPCTuningType::FORCE_ASYMPTOTIC; break;
default: tuning_type = Temperature::MPCTuningType::AUTO; break;
}
LCD_MESSAGE(MSG_MPC_AUTOTUNE);
thermalManager.MPC_autotune(e, tuning_type);
ui.reset_status();
if (TERN0(MPC_PTC, tuning_type == Temperature::MPCTuningType::FORCE_ASYMPTOTIC))
SERIAL_ECHOLNPGM("Aymptotic tuning not avaiable for PTC hotends");
else {
LCD_MESSAGE(MSG_MPC_AUTOTUNE);
thermalManager.MPC_autotune(e, tuning_type);
ui.reset_status();
}
return;
}
#endif
@ -74,6 +78,10 @@ void GcodeSuite::M306() {
if (parser.seen("ACFPRH")) {
MPC_t &mpc = thermalManager.temp_hotend[e].mpc;
if (parser.seenval('P')) mpc.heater_power = parser.value_float();
#if ENABLED(MPC_PTC)
if (parser.seenval('L')) mpc.heater_alpha = parser.value_float();
if (parser.seenval('Q')) mpc.heater_reftemp = parser.value_float();
#endif
if (parser.seenval('C')) mpc.block_heat_capacity = parser.value_float();
if (parser.seenval('R')) mpc.sensor_responsiveness = parser.value_float();
if (parser.seenval('A')) mpc.ambient_xfer_coeff_fan0 = parser.value_float();
@ -94,16 +102,20 @@ void GcodeSuite::M306_report(const bool forReplay/*=true*/) {
HOTEND_LOOP() {
report_echo_start(forReplay);
MPC_t &mpc = thermalManager.temp_hotend[e].mpc;
SERIAL_ECHOPGM(" M306 E", e,
SERIAL_ECHOLNPGM(" M306 E", e,
" P", p_float_t(mpc.heater_power, 2),
#if ENABLED(MPC_PTC)
" L", p_float_t(mpc.heater_alpha, 4),
" Q", p_float_t(mpc.heater_reftemp, 2),
#endif
" C", p_float_t(mpc.block_heat_capacity, 2),
" R", p_float_t(mpc.sensor_responsiveness, 4),
" A", p_float_t(mpc.ambient_xfer_coeff_fan0, 4)
" A", p_float_t(mpc.ambient_xfer_coeff_fan0, 4),
#if ENABLED(MPC_INCLUDE_FAN)
" F", p_float_t(mpc.fanCoefficient(), 4),
#endif
" H", p_float_t(mpc.filament_heat_capacity_permm, 4)
);
#if ENABLED(MPC_INCLUDE_FAN)
SERIAL_ECHOPGM(" F", p_float_t(mpc.fanCoefficient(), 4));
#endif
SERIAL_ECHOLNPGM(" H", p_float_t(mpc.filament_heat_capacity_permm, 4));
}
}

View file

@ -1026,6 +1026,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i
#undef MPC_AUTOTUNE
#undef MPC_EDIT_MENU
#undef MPC_AUTOTUNE_MENU
#undef MPC_PTC
#endif
#if ENABLED(MPC_INCLUDE_FAN)

View file

@ -42,7 +42,7 @@
* version was tagged.
*/
#ifndef STRING_DISTRIBUTION_DATE
#define STRING_DISTRIBUTION_DATE "2025-06-11"
#define STRING_DISTRIBUTION_DATE "2025-06-17"
#endif
/**

View file

@ -58,16 +58,13 @@
* CLCD::cmd() Send 32-Bit Value(4 Bytes)CMD Buffer *
* CLCD::cmd() Send Data Structure with 32-Bit Cmd *
* CLCD::str() Send Text String in 32-Bit Multiples *
* *
* FT800/810 GRAPHIC COMMANDS *
* *
* class CLCD:CommandFifo {} Class to control Cmd FIFO *
* CommandFifo::start() Wait for CP finish - Set FIFO Ptr *
* CommandFifo::execute() Set REG_CMD_WRITE and start CP *
* CommandFifo::reset() Set Cmd Buffer Pointers to 0 *
*
* CommandFifo::fgcolor Set Graphic Item Foreground Color *
* CommandFifo::bgcolor Set Graphic Item Background Color *
* CommandFifo::begin() Begin Drawing a Primitive *

View file

@ -3710,26 +3710,39 @@ void MarlinSettings::reset() {
#if ENABLED(MPCTEMP)
constexpr float _mpc_heater_power[] = MPC_HEATER_POWER;
static_assert(HOTENDS == COUNT(_mpc_heater_power), "MPC_HEATER_POWER requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
#if ENABLED(MPC_PTC)
constexpr float _mpc_heater_alpha[] = MPC_HEATER_ALPHA;
constexpr float _mpc_heater_reftemp[] = MPC_HEATER_REFTEMP;
static_assert(HOTENDS == COUNT(_mpc_heater_alpha), "MPC_HEATER_ALPHA requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
static_assert(HOTENDS == COUNT(_mpc_heater_reftemp), "MPC_HEATER_REFTEMP requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
#endif
constexpr float _mpc_block_heat_capacity[] = MPC_BLOCK_HEAT_CAPACITY;
static_assert(HOTENDS == COUNT(_mpc_block_heat_capacity), "MPC_BLOCK_HEAT_CAPACITY requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
constexpr float _mpc_sensor_responsiveness[] = MPC_SENSOR_RESPONSIVENESS;
static_assert(HOTENDS == COUNT(_mpc_sensor_responsiveness), "MPC_SENSOR_RESPONSIVENESS requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
constexpr float _mpc_ambient_xfer_coeff[] = MPC_AMBIENT_XFER_COEFF;
static_assert(HOTENDS == COUNT(_mpc_ambient_xfer_coeff), "MPC_AMBIENT_XFER_COEFF requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
#if ENABLED(MPC_INCLUDE_FAN)
constexpr float _mpc_ambient_xfer_coeff_fan255[] = MPC_AMBIENT_XFER_COEFF_FAN255;
static_assert(HOTENDS == COUNT(_mpc_ambient_xfer_coeff_fan255), "MPC_AMBIENT_XFER_COEFF_FAN255 requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
#endif
constexpr float _filament_heat_capacity_permm[] = FILAMENT_HEAT_CAPACITY_PERMM;
static_assert(COUNT(_mpc_heater_power) == HOTENDS, "MPC_HEATER_POWER must have HOTENDS items.");
static_assert(COUNT(_mpc_block_heat_capacity) == HOTENDS, "MPC_BLOCK_HEAT_CAPACITY must have HOTENDS items.");
static_assert(COUNT(_mpc_sensor_responsiveness) == HOTENDS, "MPC_SENSOR_RESPONSIVENESS must have HOTENDS items.");
static_assert(COUNT(_mpc_ambient_xfer_coeff) == HOTENDS, "MPC_AMBIENT_XFER_COEFF must have HOTENDS items.");
#if ENABLED(MPC_INCLUDE_FAN)
static_assert(COUNT(_mpc_ambient_xfer_coeff_fan255) == HOTENDS, "MPC_AMBIENT_XFER_COEFF_FAN255 must have HOTENDS items.");
#endif
static_assert(COUNT(_filament_heat_capacity_permm) == HOTENDS, "FILAMENT_HEAT_CAPACITY_PERMM must have HOTENDS items.");
constexpr float _filament_heat_capacity_permm[] = FILAMENT_HEAT_CAPACITY_PERMM;
static_assert(HOTENDS == COUNT(_filament_heat_capacity_permm), "FILAMENT_HEAT_CAPACITY_PERMM requires values for all (" STRINGIFY(HOTENDS) ") hotends.");
HOTEND_LOOP() {
MPC_t &mpc = thermalManager.temp_hotend[e].mpc;
mpc.heater_power = _mpc_heater_power[e];
#if ENABLED(MPC_PTC)
mpc.heater_alpha = _mpc_heater_alpha[e];
mpc.heater_reftemp = _mpc_heater_reftemp[e];
#endif
mpc.block_heat_capacity = _mpc_block_heat_capacity[e];
mpc.sensor_responsiveness = _mpc_sensor_responsiveness[e];
mpc.ambient_xfer_coeff_fan0 = _mpc_ambient_xfer_coeff[e];

View file

@ -32,9 +32,6 @@
#include "trinamic.h"
#include "../stepper.h"
#include <HardwareSerial.h>
#include <SPI.h>
enum StealthIndex : uint8_t {
LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K, STEALTH_AXIS_U, STEALTH_AXIS_V, STEALTH_AXIS_W)
};
@ -242,12 +239,12 @@ enum StealthIndex : uint8_t {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
@ -280,12 +277,12 @@ enum StealthIndex : uint8_t {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
@ -705,12 +702,12 @@ enum StealthIndex : uint8_t {
st.stored.stealthChop_enabled = stealth;
TMC2208_n::CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
@ -750,12 +747,12 @@ enum StealthIndex : uint8_t {
st.stored.stealthChop_enabled = stealth;
TMC2208_n::CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01; // blank_time = 24
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
@ -788,44 +785,68 @@ enum StealthIndex : uint8_t {
) {
st.begin();
st.Rref = TMC2240_Rref;
st.Rref = TMC2240_RREF; // Minimum: 12000 ; FLY TMC2240: 12300
TMC2240_n::GCONF_t gconf{0};
gconf.en_pwm_mode = !stealth;
st.GCONF(gconf.sr);
TMC2240_n::DRV_CONF_t drv_conf{0};
drv_conf.current_range = TMC2240_CURRENT_RANGE;
drv_conf.slope_control = TMC2240_SLOPE_CONTROL;
st.DRV_CONF(drv_conf.sr);
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
// Adjust based on user experience
TMC2240_n::CHOPCONF_t chopconf{0};
chopconf.toff = chop_init.toff; // 3 (3)
chopconf.intpol = interpolate; // true
chopconf.hend = chop_init.hend + 3; // 2 (-1)
chopconf.hstrt = chop_init.hstrt - 1; // 5 (6)
chopconf.TBL = 0b10; // 36 tCLK
chopconf.tpfd = 4; // 512 NCLK
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
st.microsteps(microsteps);
st.iholddelay(10);
st.iholddelay(6);
st.irundelay(4);
// (from Makerbase)
//st.TPOWERDOWN(10);
st.TPOWERDOWN(128); // ~2s until driver lowers to hold current
st.en_pwm_mode(stealth);
st.stored.stealthChop_enabled = stealth;
// Adjust based on user experience
TMC2240_n::PWMCONF_t pwmconf{0};
pwmconf.pwm_lim = 12;
pwmconf.pwm_reg = 8;
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.pwm_freq = 0b01;
pwmconf.pwm_grad = 14;
pwmconf.pwm_ofs = 36;
pwmconf.pwm_ofs = 29;
pwmconf.pwm_grad = 0;
pwmconf.pwm_freq = 0b00; // fPWM = 2/1024 fCLK | 16MHz clock -> 31.3kHz PWM
pwmconf.pwm_autograd = true;
pwmconf.pwm_autoscale = true;
pwmconf.freewheel = 0;
pwmconf.pwm_meas_sd_enable = false;
pwmconf.pwm_dis_reg_stst = false;
pwmconf.pwm_reg = 4;
pwmconf.pwm_lim = 12;
st.PWMCONF(pwmconf.sr);
TERN(HYBRID_THRESHOLD, st.set_pwm_thrs(hyb_thrs), UNUSED(hyb_thrs));
// (from Makerbase)
//st.GCONF(0x00);
//st.IHOLD_IRUN(0x04071f03);
//st.GSTAT(0x07);
//st.GSTAT(0x00);
st.diag0_pushpull(true);
st.GSTAT(); // Clear GSTAT
}
#endif // TMC2240
#if HAS_DRIVER(TMC2660)
@ -862,12 +883,12 @@ enum StealthIndex : uint8_t {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);
@ -900,12 +921,12 @@ enum StealthIndex : uint8_t {
st.begin();
CHOPCONF_t chopconf{0};
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.tbl = 0b01;
chopconf.toff = chop_init.toff;
chopconf.intpol = interpolate;
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
TERN_(EDGE_STEPPING, chopconf.dedge = true);
chopconf.hend = chop_init.hend + 3;
chopconf.hstrt = chop_init.hstrt - 1;
chopconf.dedge = ENABLED(EDGE_STEPPING);
st.CHOPCONF(chopconf.sr);
st.rms_current(mA, hold_multiplier);

View file

@ -1864,7 +1864,8 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
}
// Update the modeled temperatures
float blocktempdelta = hotend.soft_pwm_amount * mpc.heater_power * (MPC_dT / 127) / mpc.block_heat_capacity;
const float _heater_power = DIV_TERN(MPC_PTC, mpc.heater_power, 1.0f + mpc.heater_alpha * (hotend.modeled_block_temp - mpc.heater_reftemp));
float blocktempdelta = hotend.soft_pwm_amount * _heater_power * (MPC_dT / 127) / mpc.block_heat_capacity;
blocktempdelta += (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff * MPC_dT / mpc.block_heat_capacity;
hotend.modeled_block_temp += blocktempdelta;
@ -1888,7 +1889,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
power -= (hotend.modeled_ambient_temp - hotend.modeled_block_temp) * ambient_xfer_coeff;
}
float pid_output = power * 254.0f / mpc.heater_power + 1.0f; // Ensure correct quantization into a range of 0 to 127
float pid_output = power * 254.0f / _heater_power + 1.0f; // Ensure correct quantization into a range of 0 to 127
LIMIT(pid_output, 0, MPC_MAX);
/* <-- add a slash to enable

View file

@ -386,6 +386,10 @@ typedef struct { float p, i, d, c, f; } raw_pidcf_t;
static bool e_paused; // Pause E filament permm tracking
static int32_t e_position; // For E tracking
float heater_power; // M306 P
#if ENABLED(MPC_PTC)
float heater_alpha; // M306 L
float heater_reftemp; // M306 Q
#endif
float block_heat_capacity; // M306 C
float sensor_responsiveness; // M306 R
float ambient_xfer_coeff_fan0; // M306 A

View file

@ -37,6 +37,34 @@
#define EEPROM_EXCL_ZONE 916,926 // Ender-3S1 STM32F401 Bootloader EEPROM exclusion zone
/**
* ------
* PC6 | 1 2 | PB2
* UART2_TX PA2 | 3 4 | PA3 UART2_RX
* PB14 5 6 | PB13
* PB12 | 7 8 | PB15
* GND | 9 10 | 5V
* ------
* EXP3
*/
#define EXP3_03_PIN PA2
#define EXP3_04_PIN PA3
/**
* ----
* VCC | 1 |
* VCC | 2 |
* GND | 3 |
* PA14 | 4 |
* PA13 | 5 |
* PB1 | 6 |
* PB2 | 7 |
* PA2 | 8 | UART2_TX
* PA3 | 9 | UART2_RX
* GND | 10 |
* ----
* Touch screen Interface
*/
#include "../stm32f1/pins_CREALITY_V24S1_301.h"

View file

@ -16,7 +16,7 @@
* 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, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA

View file

@ -13,7 +13,7 @@
* 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, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA