🏗️ Support for up to 6 linear axes (#19112)
Co-authored-by: Scott Lahteine <github@thinkyhead.com>
This commit is contained in:
parent
d3c56a76e7
commit
c1fca91103
|
@ -35,7 +35,7 @@
|
||||||
*
|
*
|
||||||
* Advanced settings can be found in Configuration_adv.h
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
*/
|
*/
|
||||||
#define CONFIGURATION_H_VERSION 02000801
|
#define CONFIGURATION_H_VERSION 02000900
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
|
@ -66,6 +66,14 @@
|
||||||
//
|
//
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//=========================== FOAMCUTTER_XYUV ==============================
|
||||||
|
//===========================================================================
|
||||||
|
// For a hot wire cutter with parallel horizontal axes X, I where the hights
|
||||||
|
// of the two wire ends are controlled by parallel axes Y, J.
|
||||||
|
//
|
||||||
|
//#define FOAMCUTTER_XYUV
|
||||||
|
|
||||||
// @section info
|
// @section info
|
||||||
|
|
||||||
// Author info of this build printed to the host during boot and M115
|
// Author info of this build printed to the host during boot and M115
|
||||||
|
@ -149,6 +157,45 @@
|
||||||
// Choose your own or use a service like https://www.uuidgenerator.net/version4
|
// Choose your own or use a service like https://www.uuidgenerator.net/version4
|
||||||
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Define the number of coordinated linear axes.
|
||||||
|
* See https://github.com/DerAndere1/Marlin/wiki
|
||||||
|
* Each linear axis gets its own stepper control and endstop:
|
||||||
|
*
|
||||||
|
* Steppers: *_STEP_PIN, *_ENABLE_PIN, *_DIR_PIN, *_ENABLE_ON
|
||||||
|
* Endstops: *_STOP_PIN, USE_*MIN_PLUG, USE_*MAX_PLUG
|
||||||
|
* Axes: *_MIN_POS, *_MAX_POS, INVERT_*_DIR
|
||||||
|
* Planner: DEFAULT_AXIS_STEPS_PER_UNIT, DEFAULT_MAX_FEEDRATE
|
||||||
|
* DEFAULT_MAX_ACCELERATION, AXIS_RELATIVE_MODES,
|
||||||
|
* MICROSTEP_MODES, MANUAL_FEEDRATE
|
||||||
|
*
|
||||||
|
* :[3, 4, 5, 6]
|
||||||
|
*/
|
||||||
|
//#define LINEAR_AXES 3
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Axis codes for additional axes:
|
||||||
|
* This defines the axis code that is used in G-code commands to
|
||||||
|
* reference a specific axis.
|
||||||
|
* 'A' for rotational axis parallel to X
|
||||||
|
* 'B' for rotational axis parallel to Y
|
||||||
|
* 'C' for rotational axis parallel to Z
|
||||||
|
* 'U' for secondary linear axis parallel to X
|
||||||
|
* 'V' for secondary linear axis parallel to Y
|
||||||
|
* 'W' for secondary linear axis parallel to Z
|
||||||
|
* Regardless of the settings, firmware-internal axis IDs are
|
||||||
|
* I (AXIS4), J (AXIS5), K (AXIS6).
|
||||||
|
*/
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define AXIS4_NAME 'A' // :['A', 'B', 'C', 'U', 'V', 'W']
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define AXIS5_NAME 'B' // :['A', 'B', 'C', 'U', 'V', 'W']
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define AXIS6_NAME 'C' // :['A', 'B', 'C', 'U', 'V', 'W']
|
||||||
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
// This defines the number of extruders
|
// This defines the number of extruders
|
||||||
|
@ -691,9 +738,15 @@
|
||||||
#define USE_XMIN_PLUG
|
#define USE_XMIN_PLUG
|
||||||
#define USE_YMIN_PLUG
|
#define USE_YMIN_PLUG
|
||||||
#define USE_ZMIN_PLUG
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_IMIN_PLUG
|
||||||
|
//#define USE_JMIN_PLUG
|
||||||
|
//#define USE_KMIN_PLUG
|
||||||
//#define USE_XMAX_PLUG
|
//#define USE_XMAX_PLUG
|
||||||
//#define USE_YMAX_PLUG
|
//#define USE_YMAX_PLUG
|
||||||
//#define USE_ZMAX_PLUG
|
//#define USE_ZMAX_PLUG
|
||||||
|
//#define USE_IMAX_PLUG
|
||||||
|
//#define USE_JMAX_PLUG
|
||||||
|
//#define USE_KMAX_PLUG
|
||||||
|
|
||||||
// Enable pullup for all endstops to prevent a floating state
|
// Enable pullup for all endstops to prevent a floating state
|
||||||
#define ENDSTOPPULLUPS
|
#define ENDSTOPPULLUPS
|
||||||
|
@ -702,9 +755,15 @@
|
||||||
//#define ENDSTOPPULLUP_XMAX
|
//#define ENDSTOPPULLUP_XMAX
|
||||||
//#define ENDSTOPPULLUP_YMAX
|
//#define ENDSTOPPULLUP_YMAX
|
||||||
//#define ENDSTOPPULLUP_ZMAX
|
//#define ENDSTOPPULLUP_ZMAX
|
||||||
|
//#define ENDSTOPPULLUP_IMAX
|
||||||
|
//#define ENDSTOPPULLUP_JMAX
|
||||||
|
//#define ENDSTOPPULLUP_KMAX
|
||||||
//#define ENDSTOPPULLUP_XMIN
|
//#define ENDSTOPPULLUP_XMIN
|
||||||
//#define ENDSTOPPULLUP_YMIN
|
//#define ENDSTOPPULLUP_YMIN
|
||||||
//#define ENDSTOPPULLUP_ZMIN
|
//#define ENDSTOPPULLUP_ZMIN
|
||||||
|
//#define ENDSTOPPULLUP_IMIN
|
||||||
|
//#define ENDSTOPPULLUP_JMIN
|
||||||
|
//#define ENDSTOPPULLUP_KMIN
|
||||||
//#define ENDSTOPPULLUP_ZMIN_PROBE
|
//#define ENDSTOPPULLUP_ZMIN_PROBE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -715,9 +774,15 @@
|
||||||
//#define ENDSTOPPULLDOWN_XMAX
|
//#define ENDSTOPPULLDOWN_XMAX
|
||||||
//#define ENDSTOPPULLDOWN_YMAX
|
//#define ENDSTOPPULLDOWN_YMAX
|
||||||
//#define ENDSTOPPULLDOWN_ZMAX
|
//#define ENDSTOPPULLDOWN_ZMAX
|
||||||
|
//#define ENDSTOPPULLDOWN_IMAX
|
||||||
|
//#define ENDSTOPPULLDOWN_JMAX
|
||||||
|
//#define ENDSTOPPULLDOWN_KMAX
|
||||||
//#define ENDSTOPPULLDOWN_XMIN
|
//#define ENDSTOPPULLDOWN_XMIN
|
||||||
//#define ENDSTOPPULLDOWN_YMIN
|
//#define ENDSTOPPULLDOWN_YMIN
|
||||||
//#define ENDSTOPPULLDOWN_ZMIN
|
//#define ENDSTOPPULLDOWN_ZMIN
|
||||||
|
//#define ENDSTOPPULLDOWN_IMIN
|
||||||
|
//#define ENDSTOPPULLDOWN_JMIN
|
||||||
|
//#define ENDSTOPPULLDOWN_KMIN
|
||||||
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
|
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -725,9 +790,15 @@
|
||||||
#define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define X_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define Y_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define Z_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define I_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define J_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define K_MIN_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define X_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define Y_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
#define Z_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define I_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define J_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
|
#define K_MAX_ENDSTOP_INVERTING false // Set to true to invert the logic of the endstop.
|
||||||
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe.
|
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // Set to true to invert the logic of the probe.
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -756,6 +827,9 @@
|
||||||
//#define Z2_DRIVER_TYPE A4988
|
//#define Z2_DRIVER_TYPE A4988
|
||||||
//#define Z3_DRIVER_TYPE A4988
|
//#define Z3_DRIVER_TYPE A4988
|
||||||
//#define Z4_DRIVER_TYPE A4988
|
//#define Z4_DRIVER_TYPE A4988
|
||||||
|
//#define I_DRIVER_TYPE A4988
|
||||||
|
//#define J_DRIVER_TYPE A4988
|
||||||
|
//#define K_DRIVER_TYPE A4988
|
||||||
#define E0_DRIVER_TYPE A4988
|
#define E0_DRIVER_TYPE A4988
|
||||||
//#define E1_DRIVER_TYPE A4988
|
//#define E1_DRIVER_TYPE A4988
|
||||||
//#define E2_DRIVER_TYPE A4988
|
//#define E2_DRIVER_TYPE A4988
|
||||||
|
@ -809,14 +883,14 @@
|
||||||
/**
|
/**
|
||||||
* Default Axis Steps Per Unit (steps/mm)
|
* Default Axis Steps Per Unit (steps/mm)
|
||||||
* Override with M92
|
* Override with M92
|
||||||
* X, Y, Z, E0 [, E1[, E2...]]
|
* 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, 500 }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Default Max Feed Rate (mm/s)
|
* Default Max Feed Rate (mm/s)
|
||||||
* Override with M203
|
* Override with M203
|
||||||
* X, Y, Z, E0 [, E1[, E2...]]
|
* X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
|
||||||
*/
|
*/
|
||||||
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
|
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
|
||||||
|
|
||||||
|
@ -829,7 +903,7 @@
|
||||||
* Default Max Acceleration (change/s) change = mm/s
|
* Default Max Acceleration (change/s) change = mm/s
|
||||||
* (Maximum start speed for accelerated moves)
|
* (Maximum start speed for accelerated moves)
|
||||||
* Override with M201
|
* Override with M201
|
||||||
* X, Y, Z, E0 [, E1[, E2...]]
|
* X, Y, Z [, I [, J [, K]]], E0 [, E1[, E2...]]
|
||||||
*/
|
*/
|
||||||
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
|
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
|
||||||
|
|
||||||
|
@ -863,6 +937,9 @@
|
||||||
#define DEFAULT_XJERK 10.0
|
#define DEFAULT_XJERK 10.0
|
||||||
#define DEFAULT_YJERK 10.0
|
#define DEFAULT_YJERK 10.0
|
||||||
#define DEFAULT_ZJERK 0.3
|
#define DEFAULT_ZJERK 0.3
|
||||||
|
//#define DEFAULT_IJERK 0.3
|
||||||
|
//#define DEFAULT_JJERK 0.3
|
||||||
|
//#define DEFAULT_KJERK 0.3
|
||||||
|
|
||||||
//#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves
|
//#define TRAVEL_EXTRA_XYJERK 0.0 // Additional jerk allowance for all travel moves
|
||||||
|
|
||||||
|
@ -1177,12 +1254,18 @@
|
||||||
#define Y_ENABLE_ON 0
|
#define Y_ENABLE_ON 0
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
//#define I_ENABLE_ON 0
|
||||||
|
//#define J_ENABLE_ON 0
|
||||||
|
//#define K_ENABLE_ON 0
|
||||||
|
|
||||||
// Disable axis steppers immediately when they're not being stepped.
|
// Disable axis steppers immediately when they're not being stepped.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
//#define DISABLE_I false
|
||||||
|
//#define DISABLE_J false
|
||||||
|
//#define DISABLE_K false
|
||||||
|
|
||||||
// Turn off the display blinking that warns about possible accuracy reduction
|
// Turn off the display blinking that warns about possible accuracy reduction
|
||||||
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
@ -1198,6 +1281,9 @@
|
||||||
#define INVERT_X_DIR false
|
#define INVERT_X_DIR false
|
||||||
#define INVERT_Y_DIR true
|
#define INVERT_Y_DIR true
|
||||||
#define INVERT_Z_DIR false
|
#define INVERT_Z_DIR false
|
||||||
|
//#define INVERT_I_DIR false
|
||||||
|
//#define INVERT_J_DIR false
|
||||||
|
//#define INVERT_K_DIR false
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -1233,6 +1319,9 @@
|
||||||
#define X_HOME_DIR -1
|
#define X_HOME_DIR -1
|
||||||
#define Y_HOME_DIR -1
|
#define Y_HOME_DIR -1
|
||||||
#define Z_HOME_DIR -1
|
#define Z_HOME_DIR -1
|
||||||
|
//#define I_HOME_DIR -1
|
||||||
|
//#define J_HOME_DIR -1
|
||||||
|
//#define K_HOME_DIR -1
|
||||||
|
|
||||||
// @section machine
|
// @section machine
|
||||||
|
|
||||||
|
@ -1247,6 +1336,12 @@
|
||||||
#define X_MAX_POS X_BED_SIZE
|
#define X_MAX_POS X_BED_SIZE
|
||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
//#define I_MIN_POS 0
|
||||||
|
//#define I_MAX_POS 50
|
||||||
|
//#define J_MIN_POS 0
|
||||||
|
//#define J_MAX_POS 50
|
||||||
|
//#define K_MIN_POS 0
|
||||||
|
//#define K_MAX_POS 50
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Software Endstops
|
* Software Endstops
|
||||||
|
@ -1263,6 +1358,9 @@
|
||||||
#define MIN_SOFTWARE_ENDSTOP_X
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
#define MIN_SOFTWARE_ENDSTOP_Y
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
#define MIN_SOFTWARE_ENDSTOP_Z
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_I
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_J
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_K
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Max software endstops constrain movement within maximum coordinate bounds
|
// Max software endstops constrain movement within maximum coordinate bounds
|
||||||
|
@ -1271,6 +1369,9 @@
|
||||||
#define MAX_SOFTWARE_ENDSTOP_X
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
#define MAX_SOFTWARE_ENDSTOP_Y
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
#define MAX_SOFTWARE_ENDSTOP_Z
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_I
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_J
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_K
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
|
#if EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
@ -1582,6 +1683,9 @@
|
||||||
//#define MANUAL_X_HOME_POS 0
|
//#define MANUAL_X_HOME_POS 0
|
||||||
//#define MANUAL_Y_HOME_POS 0
|
//#define MANUAL_Y_HOME_POS 0
|
||||||
//#define MANUAL_Z_HOME_POS 0
|
//#define MANUAL_Z_HOME_POS 0
|
||||||
|
//#define MANUAL_I_HOME_POS 0
|
||||||
|
//#define MANUAL_J_HOME_POS 0
|
||||||
|
//#define MANUAL_K_HOME_POS 0
|
||||||
|
|
||||||
// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
|
// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area.
|
||||||
//
|
//
|
||||||
|
|
|
@ -30,7 +30,7 @@
|
||||||
*
|
*
|
||||||
* Basic settings can be found in Configuration.h
|
* Basic settings can be found in Configuration.h
|
||||||
*/
|
*/
|
||||||
#define CONFIGURATION_ADV_H_VERSION 02000801
|
#define CONFIGURATION_ADV_H_VERSION 02000900
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Thermal Settings ============================
|
//============================= Thermal Settings ============================
|
||||||
|
@ -918,6 +918,9 @@
|
||||||
#define INVERT_X_STEP_PIN false
|
#define INVERT_X_STEP_PIN false
|
||||||
#define INVERT_Y_STEP_PIN false
|
#define INVERT_Y_STEP_PIN false
|
||||||
#define INVERT_Z_STEP_PIN false
|
#define INVERT_Z_STEP_PIN false
|
||||||
|
#define INVERT_I_STEP_PIN false
|
||||||
|
#define INVERT_J_STEP_PIN false
|
||||||
|
#define INVERT_K_STEP_PIN false
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -929,6 +932,9 @@
|
||||||
#define DISABLE_INACTIVE_X true
|
#define DISABLE_INACTIVE_X true
|
||||||
#define DISABLE_INACTIVE_Y true
|
#define DISABLE_INACTIVE_Y true
|
||||||
#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part!
|
#define DISABLE_INACTIVE_Z true // Set 'false' if the nozzle could fall onto your printed part!
|
||||||
|
#define DISABLE_INACTIVE_I true
|
||||||
|
#define DISABLE_INACTIVE_J true
|
||||||
|
#define DISABLE_INACTIVE_K true
|
||||||
#define DISABLE_INACTIVE_E true
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
// Default Minimum Feedrates for printing and travel moves
|
// Default Minimum Feedrates for printing and travel moves
|
||||||
|
@ -969,7 +975,7 @@
|
||||||
#if ENABLED(BACKLASH_COMPENSATION)
|
#if ENABLED(BACKLASH_COMPENSATION)
|
||||||
// Define values for backlash distance and correction.
|
// Define values for backlash distance and correction.
|
||||||
// If BACKLASH_GCODE is enabled these values are the defaults.
|
// If BACKLASH_GCODE is enabled these values are the defaults.
|
||||||
#define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm)
|
#define BACKLASH_DISTANCE_MM { 0, 0, 0 } // (mm) One value for each linear axis
|
||||||
#define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction
|
#define BACKLASH_CORRECTION 0.0 // 0.0 = no correction; 1.0 = full correction
|
||||||
|
|
||||||
// Add steps for motor direction changes on CORE kinematics
|
// Add steps for motor direction changes on CORE kinematics
|
||||||
|
@ -1040,6 +1046,13 @@
|
||||||
#define CALIBRATION_MEASURE_LEFT
|
#define CALIBRATION_MEASURE_LEFT
|
||||||
#define CALIBRATION_MEASURE_BACK
|
#define CALIBRATION_MEASURE_BACK
|
||||||
|
|
||||||
|
//#define CALIBRATION_MEASURE_IMIN
|
||||||
|
//#define CALIBRATION_MEASURE_IMAX
|
||||||
|
//#define CALIBRATION_MEASURE_JMIN
|
||||||
|
//#define CALIBRATION_MEASURE_JMAX
|
||||||
|
//#define CALIBRATION_MEASURE_KMIN
|
||||||
|
//#define CALIBRATION_MEASURE_KMAX
|
||||||
|
|
||||||
// Probing at the exact top center only works if the center is flat. If
|
// Probing at the exact top center only works if the center is flat. If
|
||||||
// probing on a screwhead or hollow washer, probe near the edges.
|
// probing on a screwhead or hollow washer, probe near the edges.
|
||||||
//#define CALIBRATION_MEASURE_AT_TOP_EDGES
|
//#define CALIBRATION_MEASURE_AT_TOP_EDGES
|
||||||
|
@ -2236,6 +2249,13 @@
|
||||||
//#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change
|
//#define EVENT_GCODE_AFTER_TOOLCHANGE "G12X" // Extra G-code to run after tool-change
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra G-code to run while executing tool-change commands. Can be used to use an additional
|
||||||
|
* stepper motor (I axis, see option LINEAR_AXES in Configuration.h) to drive the tool-changer.
|
||||||
|
*/
|
||||||
|
//#define EVENT_GCODE_TOOLCHANGE_T0 "G28 A\nG1 I0" // Extra G-code to run while executing tool-change command T0
|
||||||
|
//#define EVENT_GCODE_TOOLCHANGE_T1 "G1 A10" // Extra G-code to run while executing tool-change command T1
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Tool Sensors detect when tools have been picked up or dropped.
|
* Tool Sensors detect when tools have been picked up or dropped.
|
||||||
* Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc.
|
* Requires the pins TOOL_SENSOR1_PIN, TOOL_SENSOR2_PIN, etc.
|
||||||
|
@ -2413,6 +2433,24 @@
|
||||||
#define Z4_MICROSTEPS Z_MICROSTEPS
|
#define Z4_MICROSTEPS Z_MICROSTEPS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_I(TMC26X)
|
||||||
|
#define I_MAX_CURRENT 1000
|
||||||
|
#define I_SENSE_RESISTOR 91
|
||||||
|
#define I_MICROSTEPS 16
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_J(TMC26X)
|
||||||
|
#define J_MAX_CURRENT 1000
|
||||||
|
#define J_SENSE_RESISTOR 91
|
||||||
|
#define J_MICROSTEPS 16
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_K(TMC26X)
|
||||||
|
#define K_MAX_CURRENT 1000
|
||||||
|
#define K_SENSE_RESISTOR 91
|
||||||
|
#define K_MICROSTEPS 16
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
||||||
#define E0_MAX_CURRENT 1000
|
#define E0_MAX_CURRENT 1000
|
||||||
#define E0_SENSE_RESISTOR 91
|
#define E0_SENSE_RESISTOR 91
|
||||||
|
@ -2563,6 +2601,33 @@
|
||||||
//#define Z4_INTERPOLATE true
|
//#define Z4_INTERPOLATE true
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
#define I_CURRENT 800
|
||||||
|
#define I_CURRENT_HOME I_CURRENT
|
||||||
|
#define I_MICROSTEPS 16
|
||||||
|
#define I_RSENSE 0.11
|
||||||
|
#define I_CHAIN_POS -1
|
||||||
|
//#define I_INTERPOLATE true
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
#define J_CURRENT 800
|
||||||
|
#define J_CURRENT_HOME J_CURRENT
|
||||||
|
#define J_MICROSTEPS 16
|
||||||
|
#define J_RSENSE 0.11
|
||||||
|
#define J_CHAIN_POS -1
|
||||||
|
//#define J_INTERPOLATE true
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
#define K_CURRENT 800
|
||||||
|
#define K_CURRENT_HOME K_CURRENT
|
||||||
|
#define K_MICROSTEPS 16
|
||||||
|
#define K_RSENSE 0.11
|
||||||
|
#define K_CHAIN_POS -1
|
||||||
|
//#define K_INTERPOLATE true
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
#define E0_CURRENT 800
|
#define E0_CURRENT 800
|
||||||
#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
@ -2638,6 +2703,10 @@
|
||||||
//#define Y2_CS_PIN -1
|
//#define Y2_CS_PIN -1
|
||||||
//#define Z2_CS_PIN -1
|
//#define Z2_CS_PIN -1
|
||||||
//#define Z3_CS_PIN -1
|
//#define Z3_CS_PIN -1
|
||||||
|
//#define Z4_CS_PIN -1
|
||||||
|
//#define I_CS_PIN -1
|
||||||
|
//#define J_CS_PIN -1
|
||||||
|
//#define K_CS_PIN -1
|
||||||
//#define E0_CS_PIN -1
|
//#define E0_CS_PIN -1
|
||||||
//#define E1_CS_PIN -1
|
//#define E1_CS_PIN -1
|
||||||
//#define E2_CS_PIN -1
|
//#define E2_CS_PIN -1
|
||||||
|
@ -2677,6 +2746,9 @@
|
||||||
//#define Z2_SLAVE_ADDRESS 0
|
//#define Z2_SLAVE_ADDRESS 0
|
||||||
//#define Z3_SLAVE_ADDRESS 0
|
//#define Z3_SLAVE_ADDRESS 0
|
||||||
//#define Z4_SLAVE_ADDRESS 0
|
//#define Z4_SLAVE_ADDRESS 0
|
||||||
|
//#define I_SLAVE_ADDRESS 0
|
||||||
|
//#define J_SLAVE_ADDRESS 0
|
||||||
|
//#define K_SLAVE_ADDRESS 0
|
||||||
//#define E0_SLAVE_ADDRESS 0
|
//#define E0_SLAVE_ADDRESS 0
|
||||||
//#define E1_SLAVE_ADDRESS 0
|
//#define E1_SLAVE_ADDRESS 0
|
||||||
//#define E2_SLAVE_ADDRESS 0
|
//#define E2_SLAVE_ADDRESS 0
|
||||||
|
@ -2701,6 +2773,9 @@
|
||||||
*/
|
*/
|
||||||
#define STEALTHCHOP_XY
|
#define STEALTHCHOP_XY
|
||||||
#define STEALTHCHOP_Z
|
#define STEALTHCHOP_Z
|
||||||
|
#define STEALTHCHOP_I
|
||||||
|
#define STEALTHCHOP_J
|
||||||
|
#define STEALTHCHOP_K
|
||||||
#define STEALTHCHOP_E
|
#define STEALTHCHOP_E
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -2772,6 +2847,9 @@
|
||||||
#define Z2_HYBRID_THRESHOLD 3
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define Z3_HYBRID_THRESHOLD 3
|
#define Z3_HYBRID_THRESHOLD 3
|
||||||
#define Z4_HYBRID_THRESHOLD 3
|
#define Z4_HYBRID_THRESHOLD 3
|
||||||
|
#define I_HYBRID_THRESHOLD 3
|
||||||
|
#define J_HYBRID_THRESHOLD 3
|
||||||
|
#define K_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
|
@ -2818,6 +2896,9 @@
|
||||||
//#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
//#define Z2_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
||||||
//#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
//#define Z3_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
||||||
//#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
//#define Z4_STALL_SENSITIVITY Z_STALL_SENSITIVITY
|
||||||
|
//#define I_STALL_SENSITIVITY 8
|
||||||
|
//#define J_STALL_SENSITIVITY 8
|
||||||
|
//#define K_STALL_SENSITIVITY 8
|
||||||
//#define SPI_ENDSTOPS // TMC2130 only
|
//#define SPI_ENDSTOPS // TMC2130 only
|
||||||
//#define IMPROVE_HOMING_RELIABILITY
|
//#define IMPROVE_HOMING_RELIABILITY
|
||||||
#endif
|
#endif
|
||||||
|
@ -2958,6 +3039,33 @@
|
||||||
#define Z4_SLEW_RATE 1
|
#define Z4_SLEW_RATE 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_I(L6470)
|
||||||
|
#define I_MICROSTEPS 128
|
||||||
|
#define I_OVERCURRENT 2000
|
||||||
|
#define I_STALLCURRENT 1500
|
||||||
|
#define I_MAX_VOLTAGE 127
|
||||||
|
#define I_CHAIN_POS -1
|
||||||
|
#define I_SLEW_RATE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_J(L6470)
|
||||||
|
#define J_MICROSTEPS 128
|
||||||
|
#define J_OVERCURRENT 2000
|
||||||
|
#define J_STALLCURRENT 1500
|
||||||
|
#define J_MAX_VOLTAGE 127
|
||||||
|
#define J_CHAIN_POS -1
|
||||||
|
#define J_SLEW_RATE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_DRIVER_TYPE_K(L6470)
|
||||||
|
#define K_MICROSTEPS 128
|
||||||
|
#define K_OVERCURRENT 2000
|
||||||
|
#define K_STALLCURRENT 1500
|
||||||
|
#define K_MAX_VOLTAGE 127
|
||||||
|
#define K_CHAIN_POS -1
|
||||||
|
#define K_SLEW_RATE 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
#define E0_MICROSTEPS 128
|
#define E0_MICROSTEPS 128
|
||||||
#define E0_OVERCURRENT 2000
|
#define E0_OVERCURRENT 2000
|
||||||
|
|
|
@ -168,6 +168,51 @@ void setup_endstop_interrupts() {
|
||||||
pciSetup(Z_MIN_PIN);
|
pciSetup(Z_MIN_PIN);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MAX
|
||||||
|
#if (digitalPinToInterrupt(I_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(I_MAX_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(I_MAX_PIN), "I_MAX_PIN is not interrupt-capable");
|
||||||
|
pciSetup(I_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#elif HAS_I_MIN
|
||||||
|
#if (digitalPinToInterrupt(I_MIN_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(I_MIN_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(I_MIN_PIN), "I_MIN_PIN is not interrupt-capable");
|
||||||
|
pciSetup(I_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
#if (digitalPinToInterrupt(J_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(J_MAX_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(J_MAX_PIN), "J_MAX_PIN is not interrupt-capable");
|
||||||
|
pciSetup(J_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#elif HAS_J_MIN
|
||||||
|
#if (digitalPinToInterrupt(J_MIN_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(J_MIN_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(J_MIN_PIN), "J_MIN_PIN is not interrupt-capable");
|
||||||
|
pciSetup(J_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
#if (digitalPinToInterrupt(K_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(K_MAX_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(K_MAX_PIN), "K_MAX_PIN is not interrupt-capable");
|
||||||
|
pciSetup(K_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#elif HAS_K_MIN
|
||||||
|
#if (digitalPinToInterrupt(K_MIN_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
_ATTACH(K_MIN_PIN);
|
||||||
|
#else
|
||||||
|
static_assert(digitalPinHasPCICR(K_MIN_PIN), "K_MIN_PIN is not interrupt-capable");
|
||||||
|
pciSetup(K_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#if HAS_X2_MAX
|
#if HAS_X2_MAX
|
||||||
#if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
|
#if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
_ATTACH(X2_MAX_PIN);
|
_ATTACH(X2_MAX_PIN);
|
||||||
|
@ -256,6 +301,5 @@ void setup_endstop_interrupts() {
|
||||||
pciSetup(Z_MIN_PROBE_PIN);
|
pciSetup(Z_MIN_PROBE_PIN);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
|
// If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
|
||||||
}
|
}
|
||||||
|
|
|
@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -59,4 +59,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -122,4 +122,37 @@ void setup_endstop_interrupts() {
|
||||||
#endif
|
#endif
|
||||||
_ATTACH(Z_MIN_PROBE_PIN);
|
_ATTACH(Z_MIN_PROBE_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MAX
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(I_MAX_PIN)
|
||||||
|
#error "I_MAX_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(I_MAX_PIN);
|
||||||
|
#elif HAS_I_MIN
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(I_MIN_PIN)
|
||||||
|
#error "I_MIN_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(I_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(J_MAX_PIN)
|
||||||
|
#error "J_MAX_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(J_MAX_PIN);
|
||||||
|
#elif HAS_J_MIN
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(J_MIN_PIN)
|
||||||
|
#error "J_MIN_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(J_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(K_MAX_PIN)
|
||||||
|
#error "K_MAX_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(K_MAX_PIN);
|
||||||
|
#elif HAS_K_MIN
|
||||||
|
#if !LPC1768_PIN_INTERRUPT_M(K_MIN_PIN)
|
||||||
|
#error "K_MIN_PIN is not INTERRUPT-capable."
|
||||||
|
#endif
|
||||||
|
_ATTACH(K_MIN_PIN);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -48,79 +48,37 @@
|
||||||
#include "../../module/endstops.h"
|
#include "../../module/endstops.h"
|
||||||
|
|
||||||
#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
|
#define MATCH_EILINE(P1,P2) (P1 != P2 && PIN_TO_EILINE(P1) == PIN_TO_EILINE(P2))
|
||||||
#if HAS_X_MAX
|
#define MATCH_X_MAX_EILINE(P) TERN0(HAS_X_MAX, DEFER4(MATCH_EILINE)(P, X_MAX_PIN))
|
||||||
#define MATCH_X_MAX_EILINE(P) MATCH_EILINE(P, X_MAX_PIN)
|
#define MATCH_X_MIN_EILINE(P) TERN0(HAS_X_MIN, DEFER4(MATCH_EILINE)(P, X_MIN_PIN))
|
||||||
#else
|
#define MATCH_Y_MAX_EILINE(P) TERN0(HAS_Y_MAX, DEFER4(MATCH_EILINE)(P, Y_MAX_PIN))
|
||||||
#define MATCH_X_MAX_EILINE(P) false
|
#define MATCH_Y_MIN_EILINE(P) TERN0(HAS_Y_MIN, DEFER4(MATCH_EILINE)(P, Y_MIN_PIN))
|
||||||
#endif
|
#define MATCH_Z_MAX_EILINE(P) TERN0(HAS_Z_MAX, DEFER4(MATCH_EILINE)(P, Z_MAX_PIN))
|
||||||
#if HAS_X_MIN
|
#define MATCH_Z_MIN_EILINE(P) TERN0(HAS_Z_MIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PIN))
|
||||||
#define MATCH_X_MIN_EILINE(P) MATCH_EILINE(P, X_MIN_PIN)
|
#define MATCH_I_MAX_EILINE(P) TERN0(HAS_I_MAX, DEFER4(MATCH_EILINE)(P, I_MAX_PIN))
|
||||||
#else
|
#define MATCH_I_MIN_EILINE(P) TERN0(HAS_I_MIN, DEFER4(MATCH_EILINE)(P, I_MIN_PIN))
|
||||||
#define MATCH_X_MIN_EILINE(P) false
|
#define MATCH_J_MAX_EILINE(P) TERN0(HAS_J_MAX, DEFER4(MATCH_EILINE)(P, J_MAX_PIN))
|
||||||
#endif
|
#define MATCH_J_MIN_EILINE(P) TERN0(HAS_J_MIN, DEFER4(MATCH_EILINE)(P, J_MIN_PIN))
|
||||||
#if HAS_Y_MAX
|
#define MATCH_K_MAX_EILINE(P) TERN0(HAS_K_MAX, DEFER4(MATCH_EILINE)(P, K_MAX_PIN))
|
||||||
#define MATCH_Y_MAX_EILINE(P) MATCH_EILINE(P, Y_MAX_PIN)
|
#define MATCH_K_MIN_EILINE(P) TERN0(HAS_K_MIN, DEFER4(MATCH_EILINE)(P, K_MIN_PIN))
|
||||||
#else
|
#define MATCH_Z2_MAX_EILINE(P) TERN0(HAS_Z2_MAX, DEFER4(MATCH_EILINE)(P, Z2_MAX_PIN))
|
||||||
#define MATCH_Y_MAX_EILINE(P) false
|
#define MATCH_Z2_MIN_EILINE(P) TERN0(HAS_Z2_MIN, DEFER4(MATCH_EILINE)(P, Z2_MIN_PIN))
|
||||||
#endif
|
#define MATCH_Z3_MAX_EILINE(P) TERN0(HAS_Z3_MAX, DEFER4(MATCH_EILINE)(P, Z3_MAX_PIN))
|
||||||
#if HAS_Y_MIN
|
#define MATCH_Z3_MIN_EILINE(P) TERN0(HAS_Z3_MIN, DEFER4(MATCH_EILINE)(P, Z3_MIN_PIN))
|
||||||
#define MATCH_Y_MIN_EILINE(P) MATCH_EILINE(P, Y_MIN_PIN)
|
#define MATCH_Z4_MAX_EILINE(P) TERN0(HAS_Z4_MAX, DEFER4(MATCH_EILINE)(P, Z4_MAX_PIN))
|
||||||
#else
|
#define MATCH_Z4_MIN_EILINE(P) TERN0(HAS_Z4_MIN, DEFER4(MATCH_EILINE)(P, Z4_MIN_PIN))
|
||||||
#define MATCH_Y_MIN_EILINE(P) false
|
#define MATCH_Z_MIN_PROBE_EILINE(P) TERN0(HAS_Z_MIN_PROBE_PIN, DEFER4(MATCH_EILINE)(P, Z_MIN_PROBE_PIN))
|
||||||
#endif
|
|
||||||
#if HAS_Z_MAX
|
#define AVAILABLE_EILINE(P) ( PIN_TO_EILINE(P) != -1 \
|
||||||
#define MATCH_Z_MAX_EILINE(P) MATCH_EILINE(P, Z_MAX_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z_MAX_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z_MIN
|
|
||||||
#define MATCH_Z_MIN_EILINE(P) MATCH_EILINE(P, Z_MIN_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z_MIN_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z2_MAX
|
|
||||||
#define MATCH_Z2_MAX_EILINE(P) MATCH_EILINE(P, Z2_MAX_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z2_MAX_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z2_MIN
|
|
||||||
#define MATCH_Z2_MIN_EILINE(P) MATCH_EILINE(P, Z2_MIN_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z2_MIN_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z3_MAX
|
|
||||||
#define MATCH_Z3_MAX_EILINE(P) MATCH_EILINE(P, Z3_MAX_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z3_MAX_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z3_MIN
|
|
||||||
#define MATCH_Z3_MIN_EILINE(P) MATCH_EILINE(P, Z3_MIN_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z3_MIN_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z4_MAX
|
|
||||||
#define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z4_MAX_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z4_MIN
|
|
||||||
#define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z4_MIN_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#if HAS_Z_MIN_PROBE_PIN
|
|
||||||
#define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN)
|
|
||||||
#else
|
|
||||||
#define MATCH_Z_MIN_PROBE_EILINE(P) false
|
|
||||||
#endif
|
|
||||||
#define AVAILABLE_EILINE(P) (PIN_TO_EILINE(P) != -1 \
|
|
||||||
&& !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
|
&& !MATCH_X_MAX_EILINE(P) && !MATCH_X_MIN_EILINE(P) \
|
||||||
&& !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \
|
&& !MATCH_Y_MAX_EILINE(P) && !MATCH_Y_MIN_EILINE(P) \
|
||||||
&& !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
|
&& !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
|
||||||
|
&& !MATCH_I_MAX_EILINE(P) && !MATCH_I_MIN_EILINE(P) \
|
||||||
|
&& !MATCH_J_MAX_EILINE(P) && !MATCH_J_MIN_EILINE(P) \
|
||||||
|
&& !MATCH_K_MAX_EILINE(P) && !MATCH_K_MIN_EILINE(P) \
|
||||||
&& !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
|
&& !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
|
||||||
&& !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
|
&& !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
|
||||||
&& !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
|
&& !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
|
||||||
&& !MATCH_Z_MIN_PROBE_EILINE(P))
|
&& !MATCH_Z_MIN_PROBE_EILINE(P) )
|
||||||
|
|
||||||
// One ISR for all EXT-Interrupts
|
// One ISR for all EXT-Interrupts
|
||||||
void endstop_ISR() { endstops.update(); }
|
void endstop_ISR() { endstops.update(); }
|
||||||
|
@ -204,5 +162,37 @@ void setup_endstop_interrupts() {
|
||||||
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
|
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
|
||||||
#endif
|
#endif
|
||||||
_ATTACH(Z_MIN_PROBE_PIN);
|
_ATTACH(Z_MIN_PROBE_PIN);
|
||||||
|
#elif HAS_I_MAX
|
||||||
|
#if !AVAILABLE_EILINE(I_MAX_PIN)
|
||||||
|
#error "I_MAX_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
|
||||||
|
#elif HAS_I_MIN
|
||||||
|
#if !AVAILABLE_EILINE(I_MIN_PIN)
|
||||||
|
#error "I_MIN_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(I_MIN_PIN, endstop_ISR, CHANGE);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
#if !AVAILABLE_EILINE(J_MAX_PIN)
|
||||||
|
#error "J_MAX_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
|
||||||
|
#elif HAS_J_MIN
|
||||||
|
#if !AVAILABLE_EILINE(J_MIN_PIN)
|
||||||
|
#error "J_MIN_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(J_MIN_PIN, endstop_ISR, CHANGE);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
#if !AVAILABLE_EILINE(K_MAX_PIN)
|
||||||
|
#error "K_MAX_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
|
||||||
|
#elif HAS_K_MIN
|
||||||
|
#if !AVAILABLE_EILINE(K_MIN_PIN)
|
||||||
|
#error "K_MIN_PIN has no EXTINT line available."
|
||||||
|
#endif
|
||||||
|
attachInterrupt(K_MIN_PIN, endstop_ISR, CHANGE);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -46,4 +46,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -167,6 +167,15 @@ constexpr bool IsSerialClassAllowed(const HardwareSerial&) { return false; }
|
||||||
#if AXIS_HAS_HW_SERIAL(Z4)
|
#if AXIS_HAS_HW_SERIAL(Z4)
|
||||||
CHECK_AXIS_SERIAL(Z4);
|
CHECK_AXIS_SERIAL(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_HAS_HW_SERIAL(I)
|
||||||
|
CHECK_AXIS_SERIAL(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_HW_SERIAL(J)
|
||||||
|
CHECK_AXIS_SERIAL(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_HW_SERIAL(K)
|
||||||
|
CHECK_AXIS_SERIAL(K);
|
||||||
|
#endif
|
||||||
#if AXIS_HAS_HW_SERIAL(E0)
|
#if AXIS_HAS_HW_SERIAL(E0)
|
||||||
CHECK_AXIS_SERIAL(E0);
|
CHECK_AXIS_SERIAL(E0);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -71,4 +71,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -64,4 +64,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -63,4 +63,10 @@ void setup_endstop_interrupts() {
|
||||||
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
|
||||||
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
|
||||||
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
|
||||||
|
TERN_(HAS_I_MAX, _ATTACH(I_MAX_PIN));
|
||||||
|
TERN_(HAS_I_MIN, _ATTACH(I_MIN_PIN));
|
||||||
|
TERN_(HAS_J_MAX, _ATTACH(J_MAX_PIN));
|
||||||
|
TERN_(HAS_J_MIN, _ATTACH(J_MIN_PIN));
|
||||||
|
TERN_(HAS_K_MAX, _ATTACH(K_MAX_PIN));
|
||||||
|
TERN_(HAS_K_MIN, _ATTACH(K_MIN_PIN));
|
||||||
}
|
}
|
||||||
|
|
|
@ -304,6 +304,9 @@ void enable_all_steppers() {
|
||||||
ENABLE_AXIS_X();
|
ENABLE_AXIS_X();
|
||||||
ENABLE_AXIS_Y();
|
ENABLE_AXIS_Y();
|
||||||
ENABLE_AXIS_Z();
|
ENABLE_AXIS_Z();
|
||||||
|
ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki)
|
||||||
|
ENABLE_AXIS_J();
|
||||||
|
ENABLE_AXIS_K();
|
||||||
enable_e_steppers();
|
enable_e_steppers();
|
||||||
|
|
||||||
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled());
|
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled());
|
||||||
|
@ -325,6 +328,9 @@ void disable_all_steppers() {
|
||||||
DISABLE_AXIS_X();
|
DISABLE_AXIS_X();
|
||||||
DISABLE_AXIS_Y();
|
DISABLE_AXIS_Y();
|
||||||
DISABLE_AXIS_Z();
|
DISABLE_AXIS_Z();
|
||||||
|
DISABLE_AXIS_I();
|
||||||
|
DISABLE_AXIS_J();
|
||||||
|
DISABLE_AXIS_K();
|
||||||
disable_e_steppers();
|
disable_e_steppers();
|
||||||
|
|
||||||
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled());
|
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled());
|
||||||
|
@ -444,6 +450,9 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
|
||||||
if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X();
|
if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X();
|
||||||
if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y();
|
if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y();
|
||||||
if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z();
|
if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z();
|
||||||
|
if (ENABLED(DISABLE_INACTIVE_I)) DISABLE_AXIS_I();
|
||||||
|
if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J();
|
||||||
|
if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K();
|
||||||
if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers();
|
if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers();
|
||||||
|
|
||||||
TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
|
TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
|
||||||
|
@ -935,6 +944,15 @@ inline void tmc_standby_setup() {
|
||||||
#if PIN_EXISTS(Z4_STDBY)
|
#if PIN_EXISTS(Z4_STDBY)
|
||||||
SET_INPUT_PULLDOWN(Z4_STDBY_PIN);
|
SET_INPUT_PULLDOWN(Z4_STDBY_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
#if PIN_EXISTS(I_STDBY)
|
||||||
|
SET_INPUT_PULLDOWN(I_STDBY_PIN);
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_STDBY)
|
||||||
|
SET_INPUT_PULLDOWN(J_STDBY_PIN);
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_STDBY)
|
||||||
|
SET_INPUT_PULLDOWN(K_STDBY_PIN);
|
||||||
|
#endif
|
||||||
#if PIN_EXISTS(E0_STDBY)
|
#if PIN_EXISTS(E0_STDBY)
|
||||||
SET_INPUT_PULLDOWN(E0_STDBY_PIN);
|
SET_INPUT_PULLDOWN(E0_STDBY_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -60,6 +60,9 @@
|
||||||
#define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T)
|
#define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T)
|
||||||
#define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T)
|
#define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T)
|
||||||
#define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
|
#define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
|
||||||
|
#define AXIS_DRIVER_TYPE_I(T) _AXIS_DRIVER_TYPE(I,T)
|
||||||
|
#define AXIS_DRIVER_TYPE_J(T) _AXIS_DRIVER_TYPE(J,T)
|
||||||
|
#define AXIS_DRIVER_TYPE_K(T) _AXIS_DRIVER_TYPE(K,T)
|
||||||
|
|
||||||
#define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T))
|
#define AXIS_DRIVER_TYPE_X2(T) (EITHER(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) && _AXIS_DRIVER_TYPE(X2,T))
|
||||||
#define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
|
#define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
|
||||||
|
@ -83,6 +86,7 @@
|
||||||
#define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T))
|
#define HAS_E_DRIVER(T) (0 RREPEAT2(E_STEPPERS, _OR_ADTE, T))
|
||||||
|
|
||||||
#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \
|
#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Z(T) \
|
||||||
|
|| AXIS_DRIVER_TYPE_I(T) || AXIS_DRIVER_TYPE_J(T) || AXIS_DRIVER_TYPE_K(T) \
|
||||||
|| AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \
|
|| AXIS_DRIVER_TYPE_X2(T) || AXIS_DRIVER_TYPE_Y2(T) || AXIS_DRIVER_TYPE_Z2(T) \
|
||||||
|| AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) )
|
|| AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) || HAS_E_DRIVER(T) )
|
||||||
|
|
||||||
|
@ -153,9 +157,11 @@
|
||||||
#define _OR_EAH(N,T) || AXIS_HAS_##T(E##N)
|
#define _OR_EAH(N,T) || AXIS_HAS_##T(E##N)
|
||||||
#define E_AXIS_HAS(T) (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T))
|
#define E_AXIS_HAS(T) (0 _OR_EAH(0,T) _OR_EAH(1,T) _OR_EAH(2,T) _OR_EAH(3,T) _OR_EAH(4,T) _OR_EAH(5,T) _OR_EAH(6,T) _OR_EAH(7,T))
|
||||||
|
|
||||||
#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(Y) || AXIS_HAS_##T(Z) \
|
#define ANY_AXIS_HAS(T) ( AXIS_HAS_##T(X) || AXIS_HAS_##T(X2) \
|
||||||
|| AXIS_HAS_##T(X2) || AXIS_HAS_##T(Y2) || AXIS_HAS_##T(Z2) \
|
|| AXIS_HAS_##T(Y) || AXIS_HAS_##T(Y2) \
|
||||||
|| AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) || E_AXIS_HAS(T) )
|
|| AXIS_HAS_##T(Z) || AXIS_HAS_##T(Z2) || AXIS_HAS_##T(Z3) || AXIS_HAS_##T(Z4) \
|
||||||
|
|| AXIS_HAS_##T(I) || AXIS_HAS_##T(J) || AXIS_HAS_##T(K) \
|
||||||
|
|| E_AXIS_HAS(T) )
|
||||||
|
|
||||||
#if ANY_AXIS_HAS(STEALTHCHOP)
|
#if ANY_AXIS_HAS(STEALTHCHOP)
|
||||||
#define HAS_STEALTHCHOP 1
|
#define HAS_STEALTHCHOP 1
|
||||||
|
|
|
@ -266,18 +266,25 @@
|
||||||
#define STR_X_MAX "x_max"
|
#define STR_X_MAX "x_max"
|
||||||
#define STR_X2_MIN "x2_min"
|
#define STR_X2_MIN "x2_min"
|
||||||
#define STR_X2_MAX "x2_max"
|
#define STR_X2_MAX "x2_max"
|
||||||
#define STR_Y_MIN "y_min"
|
|
||||||
#define STR_Y_MAX "y_max"
|
#if HAS_Y_AXIS
|
||||||
#define STR_Y2_MIN "y2_min"
|
#define STR_Y_MIN "y_min"
|
||||||
#define STR_Y2_MAX "y2_max"
|
#define STR_Y_MAX "y_max"
|
||||||
#define STR_Z_MIN "z_min"
|
#define STR_Y2_MIN "y2_min"
|
||||||
#define STR_Z_MAX "z_max"
|
#define STR_Y2_MAX "y2_max"
|
||||||
#define STR_Z2_MIN "z2_min"
|
#endif
|
||||||
#define STR_Z2_MAX "z2_max"
|
|
||||||
#define STR_Z3_MIN "z3_min"
|
#if HAS_Z_AXIS
|
||||||
#define STR_Z3_MAX "z3_max"
|
#define STR_Z_MIN "z_min"
|
||||||
#define STR_Z4_MIN "z4_min"
|
#define STR_Z_MAX "z_max"
|
||||||
#define STR_Z4_MAX "z4_max"
|
#define STR_Z2_MIN "z2_min"
|
||||||
|
#define STR_Z2_MAX "z2_max"
|
||||||
|
#define STR_Z3_MIN "z3_min"
|
||||||
|
#define STR_Z3_MAX "z3_max"
|
||||||
|
#define STR_Z4_MIN "z4_min"
|
||||||
|
#define STR_Z4_MAX "z4_max"
|
||||||
|
#endif
|
||||||
|
|
||||||
#define STR_Z_PROBE "z_probe"
|
#define STR_Z_PROBE "z_probe"
|
||||||
#define STR_PROBE_EN "probe_en"
|
#define STR_PROBE_EN "probe_en"
|
||||||
#define STR_FILAMENT_RUNOUT_SENSOR "filament"
|
#define STR_FILAMENT_RUNOUT_SENSOR "filament"
|
||||||
|
@ -286,6 +293,9 @@
|
||||||
#define STR_X "X"
|
#define STR_X "X"
|
||||||
#define STR_Y "Y"
|
#define STR_Y "Y"
|
||||||
#define STR_Z "Z"
|
#define STR_Z "Z"
|
||||||
|
#define STR_I AXIS4_STR
|
||||||
|
#define STR_J AXIS5_STR
|
||||||
|
#define STR_K AXIS6_STR
|
||||||
#define STR_E "E"
|
#define STR_E "E"
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
#define STR_A "A"
|
#define STR_A "A"
|
||||||
|
@ -305,8 +315,114 @@
|
||||||
#define LCD_STR_A STR_A
|
#define LCD_STR_A STR_A
|
||||||
#define LCD_STR_B STR_B
|
#define LCD_STR_B STR_B
|
||||||
#define LCD_STR_C STR_C
|
#define LCD_STR_C STR_C
|
||||||
|
#define LCD_STR_I STR_I
|
||||||
|
#define LCD_STR_J STR_J
|
||||||
|
#define LCD_STR_K STR_K
|
||||||
#define LCD_STR_E STR_E
|
#define LCD_STR_E STR_E
|
||||||
|
|
||||||
|
// Extra Axis and Endstop Names
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#if AXIS4_NAME == 'A'
|
||||||
|
#define AXIS4_STR "A"
|
||||||
|
#define STR_I_MIN "a_min"
|
||||||
|
#define STR_I_MAX "a_max"
|
||||||
|
#elif AXIS4_NAME == 'B'
|
||||||
|
#define AXIS4_STR "B"
|
||||||
|
#define STR_I_MIN "b_min"
|
||||||
|
#define STR_I_MAX "b_max"
|
||||||
|
#elif AXIS4_NAME == 'C'
|
||||||
|
#define AXIS4_STR "C"
|
||||||
|
#define STR_I_MIN "c_min"
|
||||||
|
#define STR_I_MAX "c_max"
|
||||||
|
#elif AXIS4_NAME == 'U'
|
||||||
|
#define AXIS4_STR "U"
|
||||||
|
#define STR_I_MIN "u_min"
|
||||||
|
#define STR_I_MAX "u_max"
|
||||||
|
#elif AXIS4_NAME == 'V'
|
||||||
|
#define AXIS4_STR "V"
|
||||||
|
#define STR_I_MIN "v_min"
|
||||||
|
#define STR_I_MAX "v_max"
|
||||||
|
#elif AXIS4_NAME == 'W'
|
||||||
|
#define AXIS4_STR "W"
|
||||||
|
#define STR_I_MIN "w_min"
|
||||||
|
#define STR_I_MAX "w_max"
|
||||||
|
#else
|
||||||
|
#define AXIS4_STR "A"
|
||||||
|
#define STR_I_MIN "a_min"
|
||||||
|
#define STR_I_MAX "a_max"
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define AXIS4_STR ""
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#if AXIS5_NAME == 'A'
|
||||||
|
#define AXIS5_STR "A"
|
||||||
|
#define STR_J_MIN "a_min"
|
||||||
|
#define STR_J_MAX "a_max"
|
||||||
|
#elif AXIS5_NAME == 'B'
|
||||||
|
#define AXIS5_STR "B"
|
||||||
|
#define STR_J_MIN "b_min"
|
||||||
|
#define STR_J_MAX "b_max"
|
||||||
|
#elif AXIS5_NAME == 'C'
|
||||||
|
#define AXIS5_STR "C"
|
||||||
|
#define STR_J_MIN "c_min"
|
||||||
|
#define STR_J_MAX "c_max"
|
||||||
|
#elif AXIS5_NAME == 'U'
|
||||||
|
#define AXIS5_STR "U"
|
||||||
|
#define STR_J_MIN "u_min"
|
||||||
|
#define STR_J_MAX "u_max"
|
||||||
|
#elif AXIS5_NAME == 'V'
|
||||||
|
#define AXIS5_STR "V"
|
||||||
|
#define STR_J_MIN "v_min"
|
||||||
|
#define STR_J_MAX "v_max"
|
||||||
|
#elif AXIS5_NAME == 'W'
|
||||||
|
#define AXIS5_STR "W"
|
||||||
|
#define STR_J_MIN "w_min"
|
||||||
|
#define STR_J_MAX "w_max"
|
||||||
|
#else
|
||||||
|
#define AXIS5_STR "B"
|
||||||
|
#define STR_J_MIN "b_min"
|
||||||
|
#define STR_J_MAX "b_max"
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define AXIS5_STR ""
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#if AXIS6_NAME == 'A'
|
||||||
|
#define AXIS6_STR "A"
|
||||||
|
#define STR_K_MIN "a_min"
|
||||||
|
#define STR_K_MAX "a_max"
|
||||||
|
#elif AXIS6_NAME == 'B'
|
||||||
|
#define AXIS6_STR "B"
|
||||||
|
#define STR_K_MIN "b_min"
|
||||||
|
#define STR_K_MAX "b_max"
|
||||||
|
#elif AXIS6_NAME == 'C'
|
||||||
|
#define AXIS6_STR "C"
|
||||||
|
#define STR_K_MIN "c_min"
|
||||||
|
#define STR_K_MAX "c_max"
|
||||||
|
#elif AXIS6_NAME == 'U'
|
||||||
|
#define AXIS6_STR "U"
|
||||||
|
#define STR_K_MIN "u_min"
|
||||||
|
#define STR_K_MAX "u_max"
|
||||||
|
#elif AXIS6_NAME == 'V'
|
||||||
|
#define AXIS6_STR "V"
|
||||||
|
#define STR_K_MIN "v_min"
|
||||||
|
#define STR_K_MAX "v_max"
|
||||||
|
#elif AXIS6_NAME == 'W'
|
||||||
|
#define AXIS6_STR "W"
|
||||||
|
#define STR_K_MIN "w_min"
|
||||||
|
#define STR_K_MAX "w_max"
|
||||||
|
#else
|
||||||
|
#define AXIS6_STR "C"
|
||||||
|
#define STR_K_MIN "c_min"
|
||||||
|
#define STR_K_MAX "c_max"
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define AXIS6_STR ""
|
||||||
|
#endif
|
||||||
|
|
||||||
#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
|
#if EITHER(HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
|
||||||
|
|
||||||
// Custom characters defined in the first 8 characters of the LCD
|
// Custom characters defined in the first 8 characters of the LCD
|
||||||
|
|
|
@ -36,12 +36,21 @@
|
||||||
#define _XMIN_ 100
|
#define _XMIN_ 100
|
||||||
#define _YMIN_ 200
|
#define _YMIN_ 200
|
||||||
#define _ZMIN_ 300
|
#define _ZMIN_ 300
|
||||||
|
#define _IMIN_ 400
|
||||||
|
#define _JMIN_ 500
|
||||||
|
#define _KMIN_ 600
|
||||||
#define _XMAX_ 101
|
#define _XMAX_ 101
|
||||||
#define _YMAX_ 201
|
#define _YMAX_ 201
|
||||||
#define _ZMAX_ 301
|
#define _ZMAX_ 301
|
||||||
|
#define _IMAX_ 401
|
||||||
|
#define _JMAX_ 501
|
||||||
|
#define _KMAX_ 601
|
||||||
#define _XDIAG_ 102
|
#define _XDIAG_ 102
|
||||||
#define _YDIAG_ 202
|
#define _YDIAG_ 202
|
||||||
#define _ZDIAG_ 302
|
#define _ZDIAG_ 302
|
||||||
|
#define _IDIAG_ 502
|
||||||
|
#define _JDIAG_ 602
|
||||||
|
#define _KDIAG_ 702
|
||||||
#define _E0DIAG_ 400
|
#define _E0DIAG_ 400
|
||||||
#define _E1DIAG_ 401
|
#define _E1DIAG_ 401
|
||||||
#define _E2DIAG_ 402
|
#define _E2DIAG_ 402
|
||||||
|
|
|
@ -36,6 +36,10 @@ PGMSTR(X_LBL, "X:"); PGMSTR(Y_LBL, "Y:"); PGMSTR(Z_LBL, "Z:"); PGMST
|
||||||
PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C");
|
PGMSTR(SP_A_STR, " A"); PGMSTR(SP_B_STR, " B"); PGMSTR(SP_C_STR, " C");
|
||||||
PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E");
|
PGMSTR(SP_X_STR, " X"); PGMSTR(SP_Y_STR, " Y"); PGMSTR(SP_Z_STR, " Z"); PGMSTR(SP_E_STR, " E");
|
||||||
PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
|
PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMSTR(SP_E_LBL, " E:");
|
||||||
|
PGMSTR(I_STR, AXIS4_STR); PGMSTR(J_STR, AXIS5_STR); PGMSTR(K_STR, AXIS6_STR);
|
||||||
|
PGMSTR(I_LBL, AXIS4_STR ":"); PGMSTR(J_LBL, AXIS5_STR ":"); PGMSTR(K_LBL, AXIS6_STR ":");
|
||||||
|
PGMSTR(SP_I_STR, " " AXIS4_STR); PGMSTR(SP_J_STR, " " AXIS5_STR); PGMSTR(SP_K_STR, " " AXIS6_STR);
|
||||||
|
PGMSTR(SP_I_LBL, " " AXIS4_STR ":"); PGMSTR(SP_J_LBL, " " AXIS5_STR ":"); PGMSTR(SP_K_LBL, " " AXIS6_STR ":");
|
||||||
|
|
||||||
// Hook Meatpack if it's enabled on the first leaf
|
// Hook Meatpack if it's enabled on the first leaf
|
||||||
#if ENABLED(MEATPACK_ON_SERIAL_PORT_1)
|
#if ENABLED(MEATPACK_ON_SERIAL_PORT_1)
|
||||||
|
@ -101,11 +105,10 @@ void print_bin(uint16_t val) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void print_pos(
|
void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) {
|
||||||
LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z)
|
|
||||||
, PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/
|
|
||||||
) {
|
|
||||||
if (prefix) serialprintPGM(prefix);
|
if (prefix) serialprintPGM(prefix);
|
||||||
SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z));
|
SERIAL_ECHOPAIR_P(
|
||||||
|
LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k)
|
||||||
|
);
|
||||||
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
|
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
|
@ -29,12 +29,16 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Commonly-used strings in serial output
|
// Commonly-used strings in serial output
|
||||||
extern const char NUL_STR[], SP_P_STR[], SP_T_STR[],
|
extern const char NUL_STR[],
|
||||||
|
SP_X_STR[], SP_Y_STR[], SP_Z_STR[],
|
||||||
|
SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_E_STR[],
|
||||||
|
SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[],
|
||||||
|
SP_I_STR[], SP_J_STR[], SP_K_STR[],
|
||||||
|
SP_I_LBL[], SP_J_LBL[], SP_K_LBL[],
|
||||||
|
SP_P_STR[], SP_T_STR[],
|
||||||
X_STR[], Y_STR[], Z_STR[], E_STR[],
|
X_STR[], Y_STR[], Z_STR[], E_STR[],
|
||||||
X_LBL[], Y_LBL[], Z_LBL[], E_LBL[],
|
X_LBL[], Y_LBL[], Z_LBL[], E_LBL[],
|
||||||
SP_A_STR[], SP_B_STR[], SP_C_STR[],
|
I_LBL[], J_LBL[], K_LBL[];
|
||||||
SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[],
|
|
||||||
SP_X_LBL[], SP_Y_LBL[], SP_Z_LBL[], SP_E_LBL[];
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// Debugging flags for use by M111
|
// Debugging flags for use by M111
|
||||||
|
@ -310,13 +314,10 @@ void serialprint_truefalse(const bool tf);
|
||||||
void serial_spaces(uint8_t count);
|
void serial_spaces(uint8_t count);
|
||||||
|
|
||||||
void print_bin(const uint16_t val);
|
void print_bin(const uint16_t val);
|
||||||
void print_pos(
|
void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix=nullptr, PGM_P const suffix=nullptr);
|
||||||
LINEAR_AXIS_LIST(const_float_t x, const_float_t y, const_float_t z),
|
|
||||||
PGM_P const prefix=nullptr, PGM_P const suffix=nullptr
|
|
||||||
);
|
|
||||||
|
|
||||||
inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) {
|
inline void print_pos(const xyz_pos_t &xyz, PGM_P const prefix=nullptr, PGM_P const suffix=nullptr) {
|
||||||
print_pos(LINEAR_AXIS_LIST(xyz.x, xyz.y, xyz.z), prefix, suffix);
|
print_pos(LINEAR_AXIS_ELEM(xyz), prefix, suffix);
|
||||||
}
|
}
|
||||||
|
|
||||||
#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0)
|
#define SERIAL_POS(SUFFIX,VAR) do { print_pos(VAR, PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n")); }while(0)
|
||||||
|
|
|
@ -43,11 +43,17 @@ struct IF<true, L, R> { typedef L type; };
|
||||||
#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V)
|
#define LINEAR_AXIS_CODE(V...) CODE_N(LINEAR_AXES, V)
|
||||||
#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V)
|
#define LINEAR_AXIS_LIST(V...) LIST_N(LINEAR_AXES, V)
|
||||||
#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) }
|
#define LINEAR_AXIS_ARRAY(V...) { LINEAR_AXIS_LIST(V) }
|
||||||
|
#define LINEAR_AXIS_ARGS(T...) LINEAR_AXIS_LIST(T x, T y, T z, T i, T j, T k)
|
||||||
|
#define LINEAR_AXIS_ELEM(O) LINEAR_AXIS_LIST(O.x, O.y, O.z, O.i, O.j, O.k)
|
||||||
|
#define LINEAR_AXIS_DEFS(T,V) LINEAR_AXIS_LIST(T x=V, T y=V, T z=V, T i=V, T j=V, T k=V)
|
||||||
|
|
||||||
#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E)
|
#define LOGICAL_AXIS_GANG(E,V...) LINEAR_AXIS_GANG(V) GANG_ITEM_E(E)
|
||||||
#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E)
|
#define LOGICAL_AXIS_CODE(E,V...) LINEAR_AXIS_CODE(V) CODE_ITEM_E(E)
|
||||||
#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E)
|
#define LOGICAL_AXIS_LIST(E,V...) LINEAR_AXIS_LIST(V) LIST_ITEM_E(E)
|
||||||
#define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) }
|
#define LOGICAL_AXIS_ARRAY(E,V...) { LOGICAL_AXIS_LIST(E,V) }
|
||||||
|
#define LOGICAL_AXIS_ARGS(T...) LOGICAL_AXIS_LIST(T e, T x, T y, T z, T i, T j, T k)
|
||||||
|
#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k)
|
||||||
|
#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V)
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
#define LIST_ITEM_E(N) , N
|
#define LIST_ITEM_E(N) , N
|
||||||
|
@ -69,37 +75,37 @@ struct IF<true, L, R> { typedef L type; };
|
||||||
enum AxisEnum : uint8_t {
|
enum AxisEnum : uint8_t {
|
||||||
|
|
||||||
// Linear axes may be controlled directly or indirectly
|
// Linear axes may be controlled directly or indirectly
|
||||||
LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS),
|
LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS)
|
||||||
|
|
||||||
// Extruder axes may be considered distinctly
|
// Extruder axes may be considered distinctly
|
||||||
#define _EN_ITEM(N) E##N##_AXIS,
|
#define _EN_ITEM(N) , E##N##_AXIS
|
||||||
REPEAT(EXTRUDERS, _EN_ITEM)
|
REPEAT(EXTRUDERS, _EN_ITEM)
|
||||||
#undef _EN_ITEM
|
#undef _EN_ITEM
|
||||||
|
|
||||||
// Core also keeps toolhead directions
|
// Core also keeps toolhead directions
|
||||||
#if IS_CORE
|
#if IS_CORE
|
||||||
X_HEAD, Y_HEAD, Z_HEAD,
|
, X_HEAD, Y_HEAD, Z_HEAD
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Distinct axes, including all E and Core
|
// Distinct axes, including all E and Core
|
||||||
NUM_AXIS_ENUMS,
|
, NUM_AXIS_ENUMS
|
||||||
|
|
||||||
// Most of the time we refer only to the single E_AXIS
|
// Most of the time we refer only to the single E_AXIS
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
E_AXIS = E0_AXIS,
|
, E_AXIS = E0_AXIS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A, B, and C are for DELTA, SCARA, etc.
|
// A, B, and C are for DELTA, SCARA, etc.
|
||||||
A_AXIS = X_AXIS,
|
, A_AXIS = X_AXIS
|
||||||
#if LINEAR_AXES >= 2
|
#if LINEAR_AXES >= 2
|
||||||
B_AXIS = Y_AXIS,
|
, B_AXIS = Y_AXIS
|
||||||
#endif
|
#endif
|
||||||
#if LINEAR_AXES >= 3
|
#if LINEAR_AXES >= 3
|
||||||
C_AXIS = Z_AXIS,
|
, C_AXIS = Z_AXIS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// To refer to all or none
|
// To refer to all or none
|
||||||
ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF
|
, ALL_AXES_ENUM = 0xFE, NO_AXIS_ENUM = 0xFF
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t;
|
typedef IF<(NUM_AXIS_ENUMS > 8), uint16_t, uint8_t>::type axis_bits_t;
|
||||||
|
@ -241,9 +247,16 @@ struct XYval {
|
||||||
struct { T a, b; };
|
struct { T a, b; };
|
||||||
T pos[2];
|
T pos[2];
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Set all to 0
|
||||||
|
FI void reset() { x = y = 0; }
|
||||||
|
|
||||||
|
// Setters taking struct types and arrays
|
||||||
FI void set(const T px) { x = px; }
|
FI void set(const T px) { x = px; }
|
||||||
|
#if HAS_Y_AXIS
|
||||||
FI void set(const T px, const T py) { x = px; y = py; }
|
FI void set(const T px, const T py) { x = px; y = py; }
|
||||||
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
|
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
|
||||||
|
#endif
|
||||||
#if LINEAR_AXES > XY
|
#if LINEAR_AXES > XY
|
||||||
FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; }
|
FI void set(const T (&arr)[LINEAR_AXES]) { x = arr[0]; y = arr[1]; }
|
||||||
#endif
|
#endif
|
||||||
|
@ -253,10 +266,15 @@ struct XYval {
|
||||||
FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; }
|
FI void set(const T (&arr)[DISTINCT_AXES]) { x = arr[0]; y = arr[1]; }
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
FI void reset() { x = y = 0; }
|
|
||||||
|
// Length reduced to one dimension
|
||||||
FI T magnitude() const { return (T)sqrtf(x*x + y*y); }
|
FI T magnitude() const { return (T)sqrtf(x*x + y*y); }
|
||||||
|
// Pointer to the data as a simple array
|
||||||
FI operator T* () { return pos; }
|
FI operator T* () { return pos; }
|
||||||
|
// If any element is true then it's true
|
||||||
FI operator bool() { return x || y; }
|
FI operator bool() { return x || y; }
|
||||||
|
|
||||||
|
// Explicit copy and copies with conversion
|
||||||
FI XYval<T> copy() const { return *this; }
|
FI XYval<T> copy() const { return *this; }
|
||||||
FI XYval<T> ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; }
|
FI XYval<T> ABS() const { return { T(_ABS(x)), T(_ABS(y)) }; }
|
||||||
FI XYval<int16_t> asInt() { return { int16_t(x), int16_t(y) }; }
|
FI XYval<int16_t> asInt() { return { int16_t(x), int16_t(y) }; }
|
||||||
|
@ -268,17 +286,27 @@ struct XYval {
|
||||||
FI XYval<float> asFloat() { return { static_cast<float>(x), static_cast<float>(y) }; }
|
FI XYval<float> asFloat() { return { static_cast<float>(x), static_cast<float>(y) }; }
|
||||||
FI XYval<float> asFloat() const { return { static_cast<float>(x), static_cast<float>(y) }; }
|
FI XYval<float> asFloat() const { return { static_cast<float>(x), static_cast<float>(y) }; }
|
||||||
FI XYval<float> reciprocal() const { return { _RECIP(x), _RECIP(y) }; }
|
FI XYval<float> reciprocal() const { return { _RECIP(x), _RECIP(y) }; }
|
||||||
|
|
||||||
|
// Marlin workspace shifting is done with G92 and M206
|
||||||
FI XYval<float> asLogical() const { XYval<float> o = asFloat(); toLogical(o); return o; }
|
FI XYval<float> asLogical() const { XYval<float> o = asFloat(); toLogical(o); return o; }
|
||||||
FI XYval<float> asNative() const { XYval<float> o = asFloat(); toNative(o); return o; }
|
FI XYval<float> asNative() const { XYval<float> o = asFloat(); toNative(o); return o; }
|
||||||
|
|
||||||
|
// Cast to a type with more fields by making a new object
|
||||||
FI operator XYZval<T>() { return { x, y }; }
|
FI operator XYZval<T>() { return { x, y }; }
|
||||||
FI operator XYZval<T>() const { return { x, y }; }
|
FI operator XYZval<T>() const { return { x, y }; }
|
||||||
FI operator XYZEval<T>() { return { x, y }; }
|
FI operator XYZEval<T>() { return { x, y }; }
|
||||||
FI operator XYZEval<T>() const { return { x, y }; }
|
FI operator XYZEval<T>() const { return { x, y }; }
|
||||||
|
|
||||||
|
// Accessor via an AxisEnum (or any integer) [index]
|
||||||
FI T& operator[](const int n) { return pos[n]; }
|
FI T& operator[](const int n) { return pos[n]; }
|
||||||
FI const T& operator[](const int n) const { return pos[n]; }
|
FI const T& operator[](const int n) const { return pos[n]; }
|
||||||
|
|
||||||
|
// Assignment operator overrides do the expected thing
|
||||||
FI XYval<T>& operator= (const T v) { set(v, v ); return *this; }
|
FI XYval<T>& operator= (const T v) { set(v, v ); return *this; }
|
||||||
FI XYval<T>& operator= (const XYZval<T> &rs) { set(rs.x, rs.y); return *this; }
|
FI XYval<T>& operator= (const XYZval<T> &rs) { set(rs.x, rs.y); return *this; }
|
||||||
FI XYval<T>& operator= (const XYZEval<T> &rs) { set(rs.x, rs.y); return *this; }
|
FI XYval<T>& operator= (const XYZEval<T> &rs) { set(rs.x, rs.y); return *this; }
|
||||||
|
|
||||||
|
// Override other operators to get intuitive behaviors
|
||||||
FI XYval<T> operator+ (const XYval<T> &rs) const { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
FI XYval<T> operator+ (const XYval<T> &rs) const { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||||
FI XYval<T> operator+ (const XYval<T> &rs) { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
FI XYval<T> operator+ (const XYval<T> &rs) { XYval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||||
FI XYval<T> operator- (const XYval<T> &rs) const { XYval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
FI XYval<T> operator- (const XYval<T> &rs) const { XYval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||||
|
@ -315,6 +343,10 @@ struct XYval {
|
||||||
FI XYval<T> operator>>(const int &v) { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
FI XYval<T> operator>>(const int &v) { XYval<T> ls = *this; _RS(ls.x); _RS(ls.y); return ls; }
|
||||||
FI XYval<T> operator<<(const int &v) const { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
FI XYval<T> operator<<(const int &v) const { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||||
FI XYval<T> operator<<(const int &v) { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
FI XYval<T> operator<<(const int &v) { XYval<T> ls = *this; _LS(ls.x); _LS(ls.y); return ls; }
|
||||||
|
FI const XYval<T> operator-() const { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
||||||
|
FI XYval<T> operator-() { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
||||||
|
|
||||||
|
// Modifier operators
|
||||||
FI XYval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
FI XYval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
||||||
FI XYval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
FI XYval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
||||||
FI XYval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
FI XYval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
||||||
|
@ -328,6 +360,8 @@ struct XYval {
|
||||||
FI XYval<T>& operator*=(const int &v) { x *= v; y *= v; return *this; }
|
FI XYval<T>& operator*=(const int &v) { x *= v; y *= v; return *this; }
|
||||||
FI XYval<T>& operator>>=(const int &v) { _RS(x); _RS(y); return *this; }
|
FI XYval<T>& operator>>=(const int &v) { _RS(x); _RS(y); return *this; }
|
||||||
FI XYval<T>& operator<<=(const int &v) { _LS(x); _LS(y); return *this; }
|
FI XYval<T>& operator<<=(const int &v) { _LS(x); _LS(y); return *this; }
|
||||||
|
|
||||||
|
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||||
FI bool operator==(const XYval<T> &rs) { return x == rs.x && y == rs.y; }
|
FI bool operator==(const XYval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||||
FI bool operator==(const XYZval<T> &rs) { return x == rs.x && y == rs.y; }
|
FI bool operator==(const XYZval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||||
FI bool operator==(const XYZEval<T> &rs) { return x == rs.x && y == rs.y; }
|
FI bool operator==(const XYZEval<T> &rs) { return x == rs.x && y == rs.y; }
|
||||||
|
@ -340,8 +374,6 @@ struct XYval {
|
||||||
FI bool operator!=(const XYval<T> &rs) const { return !operator==(rs); }
|
FI bool operator!=(const XYval<T> &rs) const { return !operator==(rs); }
|
||||||
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
||||||
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
||||||
FI XYval<T> operator-() { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
|
||||||
FI const XYval<T> operator-() const { XYval<T> o = *this; o.x = -x; o.y = -y; return o; }
|
|
||||||
};
|
};
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -350,111 +382,144 @@ struct XYval {
|
||||||
template<typename T>
|
template<typename T>
|
||||||
struct XYZval {
|
struct XYZval {
|
||||||
union {
|
union {
|
||||||
struct { T LINEAR_AXIS_LIST(x, y, z); };
|
struct { T LINEAR_AXIS_ARGS(); };
|
||||||
struct { T LINEAR_AXIS_LIST(a, b, c); };
|
struct { T LINEAR_AXIS_LIST(a, b, c, u, v, w); };
|
||||||
T pos[LINEAR_AXES];
|
T pos[LINEAR_AXES];
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// Set all to 0
|
||||||
|
FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =, i =, j =, k =) 0; }
|
||||||
|
|
||||||
|
// Setters taking struct types and arrays
|
||||||
FI void set(const T px) { x = px; }
|
FI void set(const T px) { x = px; }
|
||||||
FI void set(const T px, const T py) { x = px; y = py; }
|
FI void set(const T px, const T py) { x = px; y = py; }
|
||||||
FI void set(const XYval<T> pxy) { x = pxy.x; y = pxy.y; }
|
FI void set(const XYval<T> pxy) { x = pxy.x; y = pxy.y; }
|
||||||
FI void set(const XYval<T> pxy, const T pz) { x = pxy.x; y = pxy.y; z = pz; }
|
FI void set(const XYval<T> pxy, const T pz) { LINEAR_AXIS_CODE(x = pxy.x, y = pxy.y, z = pz, NOOP, NOOP, NOOP); }
|
||||||
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
|
FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; }
|
||||||
FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
|
|
||||||
#if HAS_Z_AXIS
|
#if HAS_Z_AXIS
|
||||||
FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz))
|
FI void set(const T (&arr)[LINEAR_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
|
||||||
{ LINEAR_AXIS_CODE(x = px, y = py, z = pz); }
|
FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); }
|
||||||
#endif
|
#endif
|
||||||
#if LOGICAL_AXES > LINEAR_AXES
|
#if LOGICAL_AXES > LINEAR_AXES
|
||||||
FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
|
FI void set(const T (&arr)[LOGICAL_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
|
||||||
FI void set(LOGICAL_AXIS_LIST(const T, const T px, const T py, const T pz))
|
FI void set(LOGICAL_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k ); }
|
||||||
{ LINEAR_AXIS_CODE(x = px, y = py, z = pz); }
|
|
||||||
#if DISTINCT_AXES > LOGICAL_AXES
|
#if DISTINCT_AXES > LOGICAL_AXES
|
||||||
FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2]); }
|
FI void set(const T (&arr)[DISTINCT_AXES]) { LINEAR_AXIS_CODE(x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5]); }
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
FI void reset() { LINEAR_AXIS_GANG(x =, y =, z =) 0; }
|
#if LINEAR_AXES >= 4
|
||||||
FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z)); }
|
FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; }
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Length reduced to one dimension
|
||||||
|
FI T magnitude() const { return (T)sqrtf(LINEAR_AXIS_GANG(x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
|
||||||
|
// Pointer to the data as a simple array
|
||||||
FI operator T* () { return pos; }
|
FI operator T* () { return pos; }
|
||||||
FI operator bool() { return LINEAR_AXIS_GANG(z, || x, || y); }
|
// If any element is true then it's true
|
||||||
|
FI operator bool() { return LINEAR_AXIS_GANG(x, || y, || z, || i, || j, || k); }
|
||||||
|
|
||||||
|
// Explicit copy and copies with conversion
|
||||||
FI XYZval<T> copy() const { XYZval<T> o = *this; return o; }
|
FI XYZval<T> copy() const { XYZval<T> o = *this; return o; }
|
||||||
FI XYZval<T> ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); }
|
FI XYZval<T> ABS() const { return LINEAR_AXIS_ARRAY(T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); }
|
||||||
FI XYZval<int16_t> asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); }
|
FI XYZval<int16_t> asInt() { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
|
||||||
FI XYZval<int16_t> asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z)); }
|
FI XYZval<int16_t> asInt() const { return LINEAR_AXIS_ARRAY(int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
|
||||||
FI XYZval<int32_t> asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); }
|
FI XYZval<int32_t> asLong() { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
|
||||||
FI XYZval<int32_t> asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z)); }
|
FI XYZval<int32_t> asLong() const { return LINEAR_AXIS_ARRAY(int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
|
||||||
FI XYZval<int32_t> ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
|
FI XYZval<int32_t> ROUNDL() { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
|
||||||
FI XYZval<int32_t> ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
|
FI XYZval<int32_t> ROUNDL() const { return LINEAR_AXIS_ARRAY(int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
|
||||||
FI XYZval<float> asFloat() { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
|
FI XYZval<float> asFloat() { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
|
||||||
FI XYZval<float> asFloat() const { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
|
FI XYZval<float> asFloat() const { return LINEAR_AXIS_ARRAY(static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
|
||||||
FI XYZval<float> reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z)); }
|
FI XYZval<float> reciprocal() const { return LINEAR_AXIS_ARRAY(_RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); }
|
||||||
|
|
||||||
|
// Marlin workspace shifting is done with G92 and M206
|
||||||
FI XYZval<float> asLogical() const { XYZval<float> o = asFloat(); toLogical(o); return o; }
|
FI XYZval<float> asLogical() const { XYZval<float> o = asFloat(); toLogical(o); return o; }
|
||||||
FI XYZval<float> asNative() const { XYZval<float> o = asFloat(); toNative(o); return o; }
|
FI XYZval<float> asNative() const { XYZval<float> o = asFloat(); toNative(o); return o; }
|
||||||
|
|
||||||
|
// In-place cast to types having fewer fields
|
||||||
FI operator XYval<T>&() { return *(XYval<T>*)this; }
|
FI operator XYval<T>&() { return *(XYval<T>*)this; }
|
||||||
FI operator const XYval<T>&() const { return *(const XYval<T>*)this; }
|
FI operator const XYval<T>&() const { return *(const XYval<T>*)this; }
|
||||||
FI operator XYZEval<T>() const { return LINEAR_AXIS_ARRAY(x, y, z); }
|
|
||||||
|
// Cast to a type with more fields by making a new object
|
||||||
|
FI operator XYZEval<T>() const { return LINEAR_AXIS_ARRAY(x, y, z, i, j, k); }
|
||||||
|
|
||||||
|
// Accessor via an AxisEnum (or any integer) [index]
|
||||||
FI T& operator[](const int n) { return pos[n]; }
|
FI T& operator[](const int n) { return pos[n]; }
|
||||||
FI const T& operator[](const int n) const { return pos[n]; }
|
FI const T& operator[](const int n) const { return pos[n]; }
|
||||||
|
|
||||||
|
// Assignment operator overrides do the expected thing
|
||||||
FI XYZval<T>& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; }
|
FI XYZval<T>& operator= (const T v) { set(ARRAY_N_1(LINEAR_AXES, v)); return *this; }
|
||||||
FI XYZval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y ); return *this; }
|
FI XYZval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y ); return *this; }
|
||||||
FI XYZval<T>& operator= (const XYZEval<T> &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; }
|
FI XYZval<T>& operator= (const XYZEval<T> &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; }
|
||||||
FI XYZval<T> operator+ (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; }
|
|
||||||
FI XYZval<T> operator+ (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP ); return ls; }
|
// Override other operators to get intuitive behaviors
|
||||||
FI XYZval<T> operator- (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator+ (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator- (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator+ (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator* (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator- (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator* (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator- (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator* (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP ); return ls; }
|
FI XYZval<T> operator* (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZval<T> operator/ (const XYval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZval<T> operator/ (const XYval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, NOOP , NOOP , NOOP , NOOP ); return ls; }
|
||||||
FI XYZval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZval<T> operator+ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZval<T> operator+ (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZval<T> operator- (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZval<T> operator+ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZval<T> operator- (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZval<T> operator+ (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZval<T> operator- (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZval<T> operator- (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZval<T> operator* (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZval<T> operator/ (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZval<T> operator* (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const float &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZval<T> operator/ (const XYZEval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const float &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZval<T> operator/ (const XYZEval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZval<T> operator* (const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZval<T> operator* (const float &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZval<T> operator* (const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZval<T> operator* (const float &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZval<T> operator/ (const float &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZval<T> operator* (const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZval<T> operator/ (const float &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZval<T> operator* (const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZval<T> operator/ (const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZval<T> operator/ (const float &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZval<T> operator/ (const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZval<T> operator/ (const float &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZval<T> operator>>(const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; }
|
FI XYZval<T> operator/ (const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZval<T> operator>>(const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; }
|
FI XYZval<T> operator/ (const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZval<T> operator<<(const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; }
|
FI XYZval<T> operator>>(const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; }
|
||||||
FI XYZval<T> operator<<(const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; }
|
FI XYZval<T> operator>>(const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; }
|
||||||
FI XYZval<T>& operator+=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP ); return *this; }
|
FI XYZval<T> operator<<(const int &v) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; }
|
||||||
FI XYZval<T>& operator-=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP ); return *this; }
|
FI XYZval<T> operator<<(const int &v) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(_LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; }
|
||||||
FI XYZval<T>& operator*=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP ); return *this; }
|
FI const XYZval<T> operator-() const { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; }
|
||||||
FI XYZval<T>& operator/=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP ); return *this; }
|
FI XYZval<T> operator-() { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z, o.i = -i, o.j = -j, o.k = -k); return o; }
|
||||||
FI XYZval<T>& operator+=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; }
|
|
||||||
FI XYZval<T>& operator-=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; }
|
// Modifier operators
|
||||||
FI XYZval<T>& operator*=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; }
|
FI XYZval<T>& operator+=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; }
|
||||||
FI XYZval<T>& operator/=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; }
|
FI XYZval<T>& operator-=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; }
|
||||||
FI XYZval<T>& operator+=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z ); return *this; }
|
FI XYZval<T>& operator*=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; }
|
||||||
FI XYZval<T>& operator-=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z ); return *this; }
|
FI XYZval<T>& operator/=(const XYval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, NOOP, NOOP, NOOP, NOOP ); return *this; }
|
||||||
FI XYZval<T>& operator*=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z ); return *this; }
|
FI XYZval<T>& operator+=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
|
||||||
FI XYZval<T>& operator/=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z ); return *this; }
|
FI XYZval<T>& operator-=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
|
||||||
FI XYZval<T>& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; }
|
FI XYZval<T>& operator*=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
|
||||||
FI XYZval<T>& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v ); return *this; }
|
FI XYZval<T>& operator/=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
|
||||||
FI XYZval<T>& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z) ); return *this; }
|
FI XYZval<T>& operator+=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
|
||||||
FI XYZval<T>& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z) ); return *this; }
|
FI XYZval<T>& operator-=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
|
||||||
FI bool operator==(const XYZEval<T> &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
|
FI XYZval<T>& operator*=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
|
||||||
FI bool operator==(const XYZEval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
|
FI XYZval<T>& operator/=(const XYZEval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
|
||||||
|
FI XYZval<T>& operator*=(const float &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; }
|
||||||
|
FI XYZval<T>& operator*=(const int &v) { LINEAR_AXIS_CODE(x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; }
|
||||||
|
FI XYZval<T>& operator>>=(const int &v) { LINEAR_AXIS_CODE(_RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; }
|
||||||
|
FI XYZval<T>& operator<<=(const int &v) { LINEAR_AXIS_CODE(_LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; }
|
||||||
|
|
||||||
|
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||||
|
FI bool operator==(const XYZEval<T> &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
|
||||||
|
FI bool operator==(const XYZEval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
|
||||||
FI bool operator!=(const XYZEval<T> &rs) { return !operator==(rs); }
|
FI bool operator!=(const XYZEval<T> &rs) { return !operator==(rs); }
|
||||||
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
FI bool operator!=(const XYZEval<T> &rs) const { return !operator==(rs); }
|
||||||
FI XYZval<T> operator-() { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; }
|
|
||||||
FI const XYZval<T> operator-() const { XYZval<T> o = *this; LINEAR_AXIS_CODE(o.x = -x, o.y = -y, o.z = -z); return o; }
|
|
||||||
};
|
};
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -463,52 +528,76 @@ struct XYZval {
|
||||||
template<typename T>
|
template<typename T>
|
||||||
struct XYZEval {
|
struct XYZEval {
|
||||||
union {
|
union {
|
||||||
struct{ T LOGICAL_AXIS_LIST(e, x, y, z); };
|
struct { T LOGICAL_AXIS_ARGS(); };
|
||||||
struct{ T LINEAR_AXIS_LIST(a, b, c); };
|
struct { T LOGICAL_AXIS_LIST(_e, a, b, c, u, v, w); };
|
||||||
T pos[LOGICAL_AXES];
|
T pos[LOGICAL_AXES];
|
||||||
};
|
};
|
||||||
FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =) 0; }
|
// Reset all to 0
|
||||||
FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z)); }
|
FI void reset() { LOGICAL_AXIS_GANG(e =, x =, y =, z =, i =, j =, k =) 0; }
|
||||||
FI operator T* () { return pos; }
|
|
||||||
FI operator bool() { return false LOGICAL_AXIS_GANG(|| e, || x, || y, || z); }
|
// Setters taking struct types and arrays
|
||||||
FI void set(const T px) { x = px; }
|
FI void set(const T px) { x = px; }
|
||||||
FI void set(const T px, const T py) { x = px; y = py; }
|
FI void set(const T px, const T py) { x = px; y = py; }
|
||||||
FI void set(const XYval<T> pxy) { x = pxy.x; y = pxy.y; }
|
FI void set(const XYval<T> pxy) { x = pxy.x; y = pxy.y; }
|
||||||
FI void set(const XYZval<T> pxyz) { set(LINEAR_AXIS_LIST(pxyz.x, pxyz.y, pxyz.z)); }
|
FI void set(const XYZval<T> pxyz) { set(LINEAR_AXIS_ELEM(pxyz)); }
|
||||||
#if HAS_Z_AXIS
|
#if HAS_Z_AXIS
|
||||||
FI void set(LINEAR_AXIS_LIST(const T px, const T py, const T pz)) {
|
FI void set(LINEAR_AXIS_ARGS(const T)) { LINEAR_AXIS_CODE(a = x, b = y, c = z, u = i, v = j, w = k); }
|
||||||
LINEAR_AXIS_CODE(x = px, y = py, z = pz);
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
#if LOGICAL_AXES > LINEAR_AXES
|
#if LOGICAL_AXES > LINEAR_AXES
|
||||||
FI void set(LOGICAL_AXIS_LIST(const T pe, const T px, const T py, const T pz)) {
|
|
||||||
LOGICAL_AXIS_CODE(e = pe, x = px, y = py, z = pz);
|
|
||||||
}
|
|
||||||
FI void set(const XYval<T> pxy, const T pe) { set(pxy); e = pe; }
|
FI void set(const XYval<T> pxy, const T pe) { set(pxy); e = pe; }
|
||||||
FI void set(const XYZval<T> pxyz, const T pe) { set(pxyz); e = pe; }
|
FI void set(const XYZval<T> pxyz, const T pe) { set(pxyz); e = pe; }
|
||||||
|
FI void set(LOGICAL_AXIS_ARGS(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, u = i, v = j, w = k); }
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
FI void set(const T px, const T py, const T pz) { x = px; y = py; z = pz; }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
FI void set(const T px, const T py, const T pz, const T pi) { x = px; y = py; z = pz; i = pi; }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
FI void set(const T px, const T py, const T pz, const T pi, const T pj) { x = px; y = py; z = pz; i = pi; j = pj; }
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Length reduced to one dimension
|
||||||
|
FI T magnitude() const { return (T)sqrtf(LOGICAL_AXIS_GANG(+ e*e, + x*x, + y*y, + z*z, + i*i, + j*j, + k*k)); }
|
||||||
|
// Pointer to the data as a simple array
|
||||||
|
FI operator T* () { return pos; }
|
||||||
|
// If any element is true then it's true
|
||||||
|
FI operator bool() { return 0 LOGICAL_AXIS_GANG(|| e, || x, || y, || z, || i, || j, || k); }
|
||||||
|
|
||||||
|
// Explicit copy and copies with conversion
|
||||||
FI XYZEval<T> copy() const { XYZEval<T> o = *this; return o; }
|
FI XYZEval<T> copy() const { XYZEval<T> o = *this; return o; }
|
||||||
FI XYZEval<T> ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z))); }
|
FI XYZEval<T> ABS() const { return LOGICAL_AXIS_ARRAY(T(_ABS(e)), T(_ABS(x)), T(_ABS(y)), T(_ABS(z)), T(_ABS(i)), T(_ABS(j)), T(_ABS(k))); }
|
||||||
FI XYZEval<int16_t> asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); }
|
FI XYZEval<int16_t> asInt() { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
|
||||||
FI XYZEval<int16_t> asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z)); }
|
FI XYZEval<int16_t> asInt() const { return LOGICAL_AXIS_ARRAY(int16_t(e), int16_t(x), int16_t(y), int16_t(z), int16_t(i), int16_t(j), int16_t(k)); }
|
||||||
FI XYZEval<int32_t> asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); }
|
FI XYZEval<int32_t> asLong() { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
|
||||||
FI XYZEval<int32_t> asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z)); }
|
FI XYZEval<int32_t> asLong() const { return LOGICAL_AXIS_ARRAY(int32_t(e), int32_t(x), int32_t(y), int32_t(z), int32_t(i), int32_t(j), int32_t(k)); }
|
||||||
FI XYZEval<int32_t> ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
|
FI XYZEval<int32_t> ROUNDL() { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
|
||||||
FI XYZEval<int32_t> ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z))); }
|
FI XYZEval<int32_t> ROUNDL() const { return LOGICAL_AXIS_ARRAY(int32_t(LROUND(e)), int32_t(LROUND(x)), int32_t(LROUND(y)), int32_t(LROUND(z)), int32_t(LROUND(i)), int32_t(LROUND(j)), int32_t(LROUND(k))); }
|
||||||
FI XYZEval<float> asFloat() { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
|
FI XYZEval<float> asFloat() { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
|
||||||
FI XYZEval<float> asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)); }
|
FI XYZEval<float> asFloat() const { return LOGICAL_AXIS_ARRAY(static_cast<float>(e), static_cast<float>(x), static_cast<float>(y), static_cast<float>(z), static_cast<float>(i), static_cast<float>(j), static_cast<float>(k)); }
|
||||||
FI XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z)); }
|
FI XYZEval<float> reciprocal() const { return LOGICAL_AXIS_ARRAY(_RECIP(e), _RECIP(x), _RECIP(y), _RECIP(z), _RECIP(i), _RECIP(j), _RECIP(k)); }
|
||||||
|
|
||||||
|
// Marlin workspace shifting is done with G92 and M206
|
||||||
FI XYZEval<float> asLogical() const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
|
FI XYZEval<float> asLogical() const { XYZEval<float> o = asFloat(); toLogical(o); return o; }
|
||||||
FI XYZEval<float> asNative() const { XYZEval<float> o = asFloat(); toNative(o); return o; }
|
FI XYZEval<float> asNative() const { XYZEval<float> o = asFloat(); toNative(o); return o; }
|
||||||
|
|
||||||
|
// In-place cast to types having fewer fields
|
||||||
FI operator XYval<T>&() { return *(XYval<T>*)this; }
|
FI operator XYval<T>&() { return *(XYval<T>*)this; }
|
||||||
FI operator const XYval<T>&() const { return *(const XYval<T>*)this; }
|
FI operator const XYval<T>&() const { return *(const XYval<T>*)this; }
|
||||||
FI operator XYZval<T>&() { return *(XYZval<T>*)this; }
|
FI operator XYZval<T>&() { return *(XYZval<T>*)this; }
|
||||||
FI operator const XYZval<T>&() const { return *(const XYZval<T>*)this; }
|
FI operator const XYZval<T>&() const { return *(const XYZval<T>*)this; }
|
||||||
|
|
||||||
|
// Accessor via an AxisEnum (or any integer) [index]
|
||||||
FI T& operator[](const int n) { return pos[n]; }
|
FI T& operator[](const int n) { return pos[n]; }
|
||||||
FI const T& operator[](const int n) const { return pos[n]; }
|
FI const T& operator[](const int n) const { return pos[n]; }
|
||||||
|
|
||||||
|
// Assignment operator overrides do the expected thing
|
||||||
FI XYZEval<T>& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; }
|
FI XYZEval<T>& operator= (const T v) { set(LIST_N_1(LINEAR_AXES, v)); return *this; }
|
||||||
FI XYZEval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y); return *this; }
|
FI XYZEval<T>& operator= (const XYval<T> &rs) { set(rs.x, rs.y); return *this; }
|
||||||
FI XYZEval<T>& operator= (const XYZval<T> &rs) { set(LINEAR_AXIS_LIST(rs.x, rs.y, rs.z)); return *this; }
|
FI XYZEval<T>& operator= (const XYZval<T> &rs) { set(LINEAR_AXIS_ELEM(rs)); return *this; }
|
||||||
|
|
||||||
|
// Override other operators to get intuitive behaviors
|
||||||
FI XYZEval<T> operator+ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
FI XYZEval<T> operator+ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||||
FI XYZEval<T> operator+ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
FI XYZEval<T> operator+ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x += rs.x; ls.y += rs.y; return ls; }
|
||||||
FI XYZEval<T> operator- (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
FI XYZEval<T> operator- (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x -= rs.x; ls.y -= rs.y; return ls; }
|
||||||
|
@ -517,55 +606,59 @@ struct XYZEval {
|
||||||
FI XYZEval<T> operator* (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
FI XYZEval<T> operator* (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x *= rs.x; ls.y *= rs.y; return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
FI XYZEval<T> operator/ (const XYval<T> &rs) const { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
FI XYZEval<T> operator/ (const XYval<T> &rs) { XYZEval<T> ls = *this; ls.x /= rs.x; ls.y /= rs.y; return ls; }
|
||||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZEval<T> operator+ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZEval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z); return ls; }
|
FI XYZEval<T> operator+ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZEval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZEval<T> operator- (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z); return ls; }
|
FI XYZEval<T> operator- (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZEval<T> operator* (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z); return ls; }
|
FI XYZEval<T> operator* (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZEval<T> operator/ (const XYZval<T> &rs) const { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z); return ls; }
|
FI XYZEval<T> operator/ (const XYZval<T> &rs) { XYZval<T> ls = *this; LINEAR_AXIS_CODE(ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; }
|
FI XYZEval<T> operator+ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZEval<T> operator+ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z ); return ls; }
|
FI XYZEval<T> operator+ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e += rs.e, ls.x += rs.x, ls.y += rs.y, ls.z += rs.z, ls.i += rs.i, ls.j += rs.j, ls.k += rs.k); return ls; }
|
||||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; }
|
FI XYZEval<T> operator- (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator- (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z ); return ls; }
|
FI XYZEval<T> operator- (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e -= rs.e, ls.x -= rs.x, ls.y -= rs.y, ls.z -= rs.z, ls.i -= rs.i, ls.j -= rs.j, ls.k -= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; }
|
FI XYZEval<T> operator* (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator* (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z ); return ls; }
|
FI XYZEval<T> operator* (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= rs.e, ls.x *= rs.x, ls.y *= rs.y, ls.z *= rs.z, ls.i *= rs.i, ls.j *= rs.j, ls.k *= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; }
|
FI XYZEval<T> operator/ (const XYZEval<T> &rs) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator/ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z ); return ls; }
|
FI XYZEval<T> operator/ (const XYZEval<T> &rs) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= rs.e, ls.x /= rs.x, ls.y /= rs.y, ls.z /= rs.z, ls.i /= rs.i, ls.j /= rs.j, ls.k /= rs.k); return ls; }
|
||||||
FI XYZEval<T> operator* (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZEval<T> operator* (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZEval<T> operator* (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZEval<T> operator* (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZEval<T> operator* (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZEval<T> operator* (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZEval<T> operator* (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v ); return ls; }
|
FI XYZEval<T> operator* (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e *= v, ls.x *= v, ls.y *= v, ls.z *= v, ls.i *= v, ls.j *= v, ls.k *= v ); return ls; }
|
||||||
FI XYZEval<T> operator/ (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZEval<T> operator/ (const float &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZEval<T> operator/ (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZEval<T> operator/ (const float &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZEval<T> operator/ (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZEval<T> operator/ (const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZEval<T> operator/ (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v ); return ls; }
|
FI XYZEval<T> operator/ (const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(ls.e /= v, ls.x /= v, ls.y /= v, ls.z /= v, ls.i /= v, ls.j /= v, ls.k /= v ); return ls; }
|
||||||
FI XYZEval<T> operator>>(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; }
|
FI XYZEval<T> operator>>(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; }
|
||||||
FI XYZEval<T> operator>>(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z) ); return ls; }
|
FI XYZEval<T> operator>>(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_RS(ls.e), _RS(ls.x), _RS(ls.y), _RS(ls.z), _RS(ls.i), _RS(ls.j), _RS(ls.k) ); return ls; }
|
||||||
FI XYZEval<T> operator<<(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; }
|
FI XYZEval<T> operator<<(const int &v) const { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; }
|
||||||
FI XYZEval<T> operator<<(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z) ); return ls; }
|
FI XYZEval<T> operator<<(const int &v) { XYZEval<T> ls = *this; LOGICAL_AXIS_CODE(_LS(ls.e), _LS(ls.x), _LS(ls.y), _LS(ls.z), _LS(ls.i), _LS(ls.j), _LS(ls.k) ); return ls; }
|
||||||
|
FI const XYZEval<T> operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
|
||||||
|
FI XYZEval<T> operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z, -i, -j, -k); }
|
||||||
|
|
||||||
|
// Modifier operators
|
||||||
FI XYZEval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
FI XYZEval<T>& operator+=(const XYval<T> &rs) { x += rs.x; y += rs.y; return *this; }
|
||||||
FI XYZEval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
FI XYZEval<T>& operator-=(const XYval<T> &rs) { x -= rs.x; y -= rs.y; return *this; }
|
||||||
FI XYZEval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
FI XYZEval<T>& operator*=(const XYval<T> &rs) { x *= rs.x; y *= rs.y; return *this; }
|
||||||
FI XYZEval<T>& operator/=(const XYval<T> &rs) { x /= rs.x; y /= rs.y; return *this; }
|
FI XYZEval<T>& operator/=(const XYval<T> &rs) { x /= rs.x; y /= rs.y; return *this; }
|
||||||
FI XYZEval<T>& operator+=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z); return *this; }
|
FI XYZEval<T>& operator+=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator-=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z); return *this; }
|
FI XYZEval<T>& operator-=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator*=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z); return *this; }
|
FI XYZEval<T>& operator*=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator/=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z); return *this; }
|
FI XYZEval<T>& operator/=(const XYZval<T> &rs) { LINEAR_AXIS_CODE(x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator+=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z); return *this; }
|
FI XYZEval<T>& operator+=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e += rs.e, x += rs.x, y += rs.y, z += rs.z, i += rs.i, j += rs.j, k += rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator-=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z); return *this; }
|
FI XYZEval<T>& operator-=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e -= rs.e, x -= rs.x, y -= rs.y, z -= rs.z, i -= rs.i, j -= rs.j, k -= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator*=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z); return *this; }
|
FI XYZEval<T>& operator*=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e *= rs.e, x *= rs.x, y *= rs.y, z *= rs.z, i *= rs.i, j *= rs.j, k *= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator/=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z); return *this; }
|
FI XYZEval<T>& operator/=(const XYZEval<T> &rs) { LOGICAL_AXIS_CODE(e /= rs.e, x /= rs.x, y /= rs.y, z /= rs.z, i /= rs.i, j /= rs.j, k /= rs.k); return *this; }
|
||||||
FI XYZEval<T>& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v); return *this; }
|
FI XYZEval<T>& operator*=(const T &v) { LOGICAL_AXIS_CODE(e *= v, x *= v, y *= v, z *= v, i *= v, j *= v, k *= v); return *this; }
|
||||||
FI XYZEval<T>& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z)); return *this; }
|
FI XYZEval<T>& operator>>=(const int &v) { LOGICAL_AXIS_CODE(_RS(e), _RS(x), _RS(y), _RS(z), _RS(i), _RS(j), _RS(k)); return *this; }
|
||||||
FI XYZEval<T>& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z)); return *this; }
|
FI XYZEval<T>& operator<<=(const int &v) { LOGICAL_AXIS_CODE(_LS(e), _LS(x), _LS(y), _LS(z), _LS(i), _LS(j), _LS(k)); return *this; }
|
||||||
FI bool operator==(const XYZval<T> &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
|
|
||||||
FI bool operator==(const XYZval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z); }
|
// Exact comparisons. For floats a "NEAR" operation may be better.
|
||||||
|
FI bool operator==(const XYZval<T> &rs) { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
|
||||||
|
FI bool operator==(const XYZval<T> &rs) const { return true LINEAR_AXIS_GANG(&& x == rs.x, && y == rs.y, && z == rs.z, && i == rs.i, && j == rs.j, && k == rs.k); }
|
||||||
FI bool operator!=(const XYZval<T> &rs) { return !operator==(rs); }
|
FI bool operator!=(const XYZval<T> &rs) { return !operator==(rs); }
|
||||||
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
FI bool operator!=(const XYZval<T> &rs) const { return !operator==(rs); }
|
||||||
FI XYZEval<T> operator-() { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); }
|
|
||||||
FI const XYZEval<T> operator-() const { return LOGICAL_AXIS_ARRAY(-e, -x, -y, -z); }
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#undef _RECIP
|
#undef _RECIP
|
||||||
|
|
|
@ -122,7 +122,7 @@ void safe_delay(millis_t ms) {
|
||||||
SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height);
|
SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height);
|
||||||
#endif
|
#endif
|
||||||
#if ABL_PLANAR
|
#if ABL_PLANAR
|
||||||
SERIAL_ECHOPGM("ABL Adjustment X");
|
SERIAL_ECHOPGM("ABL Adjustment");
|
||||||
LOOP_LINEAR_AXES(a) {
|
LOOP_LINEAR_AXES(a) {
|
||||||
const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
|
const float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
|
||||||
SERIAL_CHAR(' ', AXIS_CHAR(a));
|
SERIAL_CHAR(' ', AXIS_CHAR(a));
|
||||||
|
|
|
@ -77,7 +77,7 @@ public:
|
||||||
// in the range 0-100 while avoiding rounding artifacts
|
// in the range 0-100 while avoiding rounding artifacts
|
||||||
constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; }
|
constexpr uint8_t ui8_to_percent(const uint8_t i) { return (int(i) * 100 + 127) / 255; }
|
||||||
|
|
||||||
const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z');
|
const xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME);
|
||||||
|
|
||||||
#if LINEAR_AXES <= XYZ
|
#if LINEAR_AXES <= XYZ
|
||||||
#define AXIS_CHAR(A) ((char)('X' + A))
|
#define AXIS_CHAR(A) ((char)('X' + A))
|
||||||
|
|
|
@ -113,20 +113,22 @@
|
||||||
const xy_float_t ad = sign * dist;
|
const xy_float_t ad = sign * dist;
|
||||||
const bool use_x_dist = ad.x > ad.y;
|
const bool use_x_dist = ad.x > ad.y;
|
||||||
|
|
||||||
float on_axis_distance = use_x_dist ? dist.x : dist.y,
|
float on_axis_distance = use_x_dist ? dist.x : dist.y;
|
||||||
e_position = end.e - start.e,
|
|
||||||
z_position = end.z - start.z;
|
|
||||||
|
|
||||||
const float e_normalized_dist = e_position / on_axis_distance, // Allow divide by zero
|
const float z_normalized_dist = (end.z - start.z) / on_axis_distance; // Allow divide by zero
|
||||||
z_normalized_dist = z_position / on_axis_distance;
|
#if HAS_EXTRUDERS
|
||||||
|
const float e_normalized_dist = (end.e - start.e) / on_axis_distance;
|
||||||
|
const bool inf_normalized_flag = isinf(e_normalized_dist);
|
||||||
|
#endif
|
||||||
|
|
||||||
xy_int8_t icell = istart;
|
xy_int8_t icell = istart;
|
||||||
|
|
||||||
const float ratio = dist.y / dist.x, // Allow divide by zero
|
const float ratio = dist.y / dist.x, // Allow divide by zero
|
||||||
c = start.y - ratio * start.x;
|
c = start.y - ratio * start.x;
|
||||||
|
|
||||||
const bool inf_normalized_flag = isinf(e_normalized_dist),
|
const bool inf_ratio_flag = isinf(ratio);
|
||||||
inf_ratio_flag = isinf(ratio);
|
|
||||||
|
xyze_pos_t dest; // Stores XYZE for segmented moves
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Handle vertical lines that stay within one column.
|
* Handle vertical lines that stay within one column.
|
||||||
|
@ -143,34 +145,36 @@
|
||||||
* For others the next X is the same so this can continue.
|
* For others the next X is the same so this can continue.
|
||||||
* Calculate X at the next Y mesh line.
|
* Calculate X at the next Y mesh line.
|
||||||
*/
|
*/
|
||||||
const float rx = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio;
|
dest.x = inf_ratio_flag ? start.x : (next_mesh_line_y - c) / ratio;
|
||||||
|
|
||||||
float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x, icell.y)
|
float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x, icell.y)
|
||||||
* planner.fade_scaling_factor_for_z(end.z);
|
* planner.fade_scaling_factor_for_z(end.z);
|
||||||
|
|
||||||
// Undefined parts of the Mesh in z_values[][] are NAN.
|
// Undefined parts of the Mesh in z_values[][] are NAN.
|
||||||
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
||||||
if (isnan(z0)) z0 = 0.0;
|
if (isnan(z0)) z0 = 0.0;
|
||||||
|
|
||||||
const float ry = mesh_index_to_ypos(icell.y);
|
dest.y = mesh_index_to_ypos(icell.y);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Without this check, it's possible to generate a zero length move, as in the case where
|
* Without this check, it's possible to generate a zero length move, as in the case where
|
||||||
* the line is heading down, starting exactly on a mesh line boundary. Since this is rare
|
* the line is heading down, starting exactly on a mesh line boundary. Since this is rare
|
||||||
* it might be fine to remove this check and let planner.buffer_segment() filter it out.
|
* it might be fine to remove this check and let planner.buffer_segment() filter it out.
|
||||||
*/
|
*/
|
||||||
if (ry != start.y) {
|
if (dest.y != start.y) {
|
||||||
if (!inf_normalized_flag) { // fall-through faster than branch
|
if (!inf_normalized_flag) { // fall-through faster than branch
|
||||||
on_axis_distance = use_x_dist ? rx - start.x : ry - start.y;
|
on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
|
||||||
e_position = start.e + on_axis_distance * e_normalized_dist;
|
TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
|
||||||
z_position = start.z + on_axis_distance * z_normalized_dist;
|
dest.z = start.z + on_axis_distance * z_normalized_dist;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
e_position = end.e;
|
TERN_(HAS_EXTRUDERS, dest.e = end.e);
|
||||||
z_position = end.z;
|
dest.z = end.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder);
|
dest.z += z0;
|
||||||
|
planner.buffer_segment(dest, scaled_fr_mm_s, extruder);
|
||||||
|
|
||||||
} //else printf("FIRST MOVE PRUNED ");
|
} //else printf("FIRST MOVE PRUNED ");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -188,12 +192,13 @@
|
||||||
*/
|
*/
|
||||||
if (iadd.y == 0) { // Horizontal line?
|
if (iadd.y == 0) { // Horizontal line?
|
||||||
icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move.
|
icell.x += ineg.x; // Heading left? Just go to the left edge of the cell for the first move.
|
||||||
|
|
||||||
while (icell.x != iend.x + ineg.x) {
|
while (icell.x != iend.x + ineg.x) {
|
||||||
icell.x += iadd.x;
|
icell.x += iadd.x;
|
||||||
const float rx = mesh_index_to_xpos(icell.x);
|
dest.x = mesh_index_to_xpos(icell.x);
|
||||||
const float ry = ratio * rx + c; // Calculate Y at the next X mesh line
|
dest.y = ratio * dest.x + c; // Calculate Y at the next X mesh line
|
||||||
|
|
||||||
float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x, icell.y)
|
float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x, icell.y)
|
||||||
* planner.fade_scaling_factor_for_z(end.z);
|
* planner.fade_scaling_factor_for_z(end.z);
|
||||||
|
|
||||||
// Undefined parts of the Mesh in z_values[][] are NAN.
|
// Undefined parts of the Mesh in z_values[][] are NAN.
|
||||||
|
@ -205,19 +210,20 @@
|
||||||
* the line is heading left, starting exactly on a mesh line boundary. Since this is rare
|
* the line is heading left, starting exactly on a mesh line boundary. Since this is rare
|
||||||
* it might be fine to remove this check and let planner.buffer_segment() filter it out.
|
* it might be fine to remove this check and let planner.buffer_segment() filter it out.
|
||||||
*/
|
*/
|
||||||
if (rx != start.x) {
|
if (dest.x != start.x) {
|
||||||
if (!inf_normalized_flag) {
|
if (!inf_normalized_flag) {
|
||||||
on_axis_distance = use_x_dist ? rx - start.x : ry - start.y;
|
on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
|
||||||
e_position = start.e + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move
|
TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist); // Based on X or Y because the move is horizontal
|
||||||
z_position = start.z + on_axis_distance * z_normalized_dist;
|
dest.z = start.z + on_axis_distance * z_normalized_dist;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
e_position = end.e;
|
TERN_(HAS_EXTRUDERS, dest.e = end.e);
|
||||||
z_position = end.z;
|
dest.z = end.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!planner.buffer_segment(rx, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder))
|
dest.z += z0;
|
||||||
break;
|
if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
|
||||||
|
|
||||||
} //else printf("FIRST MOVE PRUNED ");
|
} //else printf("FIRST MOVE PRUNED ");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -239,57 +245,65 @@
|
||||||
while (cnt) {
|
while (cnt) {
|
||||||
|
|
||||||
const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x),
|
const float next_mesh_line_x = mesh_index_to_xpos(icell.x + iadd.x),
|
||||||
next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y),
|
next_mesh_line_y = mesh_index_to_ypos(icell.y + iadd.y);
|
||||||
ry = ratio * next_mesh_line_x + c, // Calculate Y at the next X mesh line
|
|
||||||
rx = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line
|
dest.y = ratio * next_mesh_line_x + c; // Calculate Y at the next X mesh line
|
||||||
|
dest.x = (next_mesh_line_y - c) / ratio; // Calculate X at the next Y mesh line
|
||||||
// (No need to worry about ratio == 0.
|
// (No need to worry about ratio == 0.
|
||||||
// In that case, it was already detected
|
// In that case, it was already detected
|
||||||
// as a vertical line move above.)
|
// as a vertical line move above.)
|
||||||
|
|
||||||
if (neg.x == (rx > next_mesh_line_x)) { // Check if we hit the Y line first
|
if (neg.x == (dest.x > next_mesh_line_x)) { // Check if we hit the Y line first
|
||||||
// Yes! Crossing a Y Mesh Line next
|
// Yes! Crossing a Y Mesh Line next
|
||||||
float z0 = z_correction_for_x_on_horizontal_mesh_line(rx, icell.x - ineg.x, icell.y + iadd.y)
|
float z0 = z_correction_for_x_on_horizontal_mesh_line(dest.x, icell.x - ineg.x, icell.y + iadd.y)
|
||||||
* planner.fade_scaling_factor_for_z(end.z);
|
* planner.fade_scaling_factor_for_z(end.z);
|
||||||
|
|
||||||
// Undefined parts of the Mesh in z_values[][] are NAN.
|
// Undefined parts of the Mesh in z_values[][] are NAN.
|
||||||
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
||||||
if (isnan(z0)) z0 = 0.0;
|
if (isnan(z0)) z0 = 0.0;
|
||||||
|
|
||||||
|
dest.y = next_mesh_line_y;
|
||||||
|
|
||||||
if (!inf_normalized_flag) {
|
if (!inf_normalized_flag) {
|
||||||
on_axis_distance = use_x_dist ? rx - start.x : next_mesh_line_y - start.y;
|
on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
|
||||||
e_position = start.e + on_axis_distance * e_normalized_dist;
|
TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
|
||||||
z_position = start.z + on_axis_distance * z_normalized_dist;
|
dest.z = start.z + on_axis_distance * z_normalized_dist;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
e_position = end.e;
|
TERN_(HAS_EXTRUDERS, dest.e = end.e);
|
||||||
z_position = end.z;
|
dest.z = end.z;
|
||||||
}
|
}
|
||||||
if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, scaled_fr_mm_s, extruder))
|
|
||||||
break;
|
dest.z += z0;
|
||||||
|
if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
|
||||||
|
|
||||||
icell.y += iadd.y;
|
icell.y += iadd.y;
|
||||||
cnt.y--;
|
cnt.y--;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
// Yes! Crossing a X Mesh Line next
|
// Yes! Crossing a X Mesh Line next
|
||||||
float z0 = z_correction_for_y_on_vertical_mesh_line(ry, icell.x + iadd.x, icell.y - ineg.y)
|
float z0 = z_correction_for_y_on_vertical_mesh_line(dest.y, icell.x + iadd.x, icell.y - ineg.y)
|
||||||
* planner.fade_scaling_factor_for_z(end.z);
|
* planner.fade_scaling_factor_for_z(end.z);
|
||||||
|
|
||||||
// Undefined parts of the Mesh in z_values[][] are NAN.
|
// Undefined parts of the Mesh in z_values[][] are NAN.
|
||||||
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
// Replace NAN corrections with 0.0 to prevent NAN propagation.
|
||||||
if (isnan(z0)) z0 = 0.0;
|
if (isnan(z0)) z0 = 0.0;
|
||||||
|
|
||||||
|
dest.x = next_mesh_line_x;
|
||||||
|
|
||||||
if (!inf_normalized_flag) {
|
if (!inf_normalized_flag) {
|
||||||
on_axis_distance = use_x_dist ? next_mesh_line_x - start.x : ry - start.y;
|
on_axis_distance = use_x_dist ? dest.x - start.x : dest.y - start.y;
|
||||||
e_position = start.e + on_axis_distance * e_normalized_dist;
|
TERN_(HAS_EXTRUDERS, dest.e = start.e + on_axis_distance * e_normalized_dist);
|
||||||
z_position = start.z + on_axis_distance * z_normalized_dist;
|
dest.z = start.z + on_axis_distance * z_normalized_dist;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
e_position = end.e;
|
TERN_(HAS_EXTRUDERS, dest.e = end.e);
|
||||||
z_position = end.z;
|
dest.z = end.z;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!planner.buffer_segment(next_mesh_line_x, ry, z_position + z0, e_position, scaled_fr_mm_s, extruder))
|
dest.z += z0;
|
||||||
break;
|
if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
|
||||||
|
|
||||||
icell.x += iadd.x;
|
icell.x += iadd.x;
|
||||||
cnt.x--;
|
cnt.x--;
|
||||||
}
|
}
|
||||||
|
@ -438,11 +452,9 @@
|
||||||
#endif
|
#endif
|
||||||
;
|
;
|
||||||
|
|
||||||
planner.buffer_line(raw.x, raw.y, raw.z + z_cxcy, raw.e, scaled_fr_mm_s, active_extruder, segment_xyz_mm
|
const float oldz = raw.z; raw.z += z_cxcy;
|
||||||
#if ENABLED(SCARA_FEEDRATE_SCALING)
|
planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, segment_xyz_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration) );
|
||||||
, inv_duration
|
raw.z = oldz;
|
||||||
#endif
|
|
||||||
);
|
|
||||||
|
|
||||||
if (segments == 0) // done with last segment
|
if (segments == 0) // done with last segment
|
||||||
return false; // didn't set current from destination
|
return false; // didn't set current from destination
|
||||||
|
|
|
@ -417,6 +417,21 @@
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
if (monitor_tmc_driver(stepperI, need_update_error_counters, need_debug_reporting))
|
||||||
|
step_current_down(stepperI);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
if (monitor_tmc_driver(stepperJ, need_update_error_counters, need_debug_reporting))
|
||||||
|
step_current_down(stepperJ);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
if (monitor_tmc_driver(stepperK, need_update_error_counters, need_debug_reporting))
|
||||||
|
step_current_down(stepperK);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
(void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting);
|
(void)monitor_tmc_driver(stepperE0, need_update_error_counters, need_debug_reporting);
|
||||||
#endif
|
#endif
|
||||||
|
@ -757,138 +772,148 @@
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void tmc_debug_loop(
|
static void tmc_debug_loop(const TMC_debug_enum n, LOGICAL_AXIS_ARGS(const bool)) {
|
||||||
const TMC_debug_enum i,
|
if (x) {
|
||||||
LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
|
|
||||||
) {
|
|
||||||
if (print_x) {
|
|
||||||
#if AXIS_IS_TMC(X)
|
#if AXIS_IS_TMC(X)
|
||||||
tmc_status(stepperX, i);
|
tmc_status(stepperX, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(X2)
|
#if AXIS_IS_TMC(X2)
|
||||||
tmc_status(stepperX2, i);
|
tmc_status(stepperX2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
if (TERN0(HAS_Y_AXIS, y)) {
|
||||||
if (print_y) {
|
|
||||||
#if AXIS_IS_TMC(Y)
|
#if AXIS_IS_TMC(Y)
|
||||||
tmc_status(stepperY, i);
|
tmc_status(stepperY, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Y2)
|
#if AXIS_IS_TMC(Y2)
|
||||||
tmc_status(stepperY2, i);
|
tmc_status(stepperY2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (TERN0(HAS_Z_AXIS, print_z)) {
|
if (TERN0(HAS_Z_AXIS, z)) {
|
||||||
#if AXIS_IS_TMC(Z)
|
#if AXIS_IS_TMC(Z)
|
||||||
tmc_status(stepperZ, i);
|
tmc_status(stepperZ, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z2)
|
#if AXIS_IS_TMC(Z2)
|
||||||
tmc_status(stepperZ2, i);
|
tmc_status(stepperZ2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z3)
|
#if AXIS_IS_TMC(Z3)
|
||||||
tmc_status(stepperZ3, i);
|
tmc_status(stepperZ3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
tmc_status(stepperZ4, i);
|
tmc_status(stepperZ4, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (TERN0(HAS_EXTRUDERS, print_e)) {
|
#if AXIS_IS_TMC(I)
|
||||||
|
if (i) tmc_status(stepperI, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
if (j) tmc_status(stepperJ, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
if (k) tmc_status(stepperK, n);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (TERN0(HAS_EXTRUDERS, e)) {
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
tmc_status(stepperE0, i);
|
tmc_status(stepperE0, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E1)
|
#if AXIS_IS_TMC(E1)
|
||||||
tmc_status(stepperE1, i);
|
tmc_status(stepperE1, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E2)
|
#if AXIS_IS_TMC(E2)
|
||||||
tmc_status(stepperE2, i);
|
tmc_status(stepperE2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E3)
|
#if AXIS_IS_TMC(E3)
|
||||||
tmc_status(stepperE3, i);
|
tmc_status(stepperE3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E4)
|
#if AXIS_IS_TMC(E4)
|
||||||
tmc_status(stepperE4, i);
|
tmc_status(stepperE4, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E5)
|
#if AXIS_IS_TMC(E5)
|
||||||
tmc_status(stepperE5, i);
|
tmc_status(stepperE5, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E6)
|
#if AXIS_IS_TMC(E6)
|
||||||
tmc_status(stepperE6, i);
|
tmc_status(stepperE6, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E7)
|
#if AXIS_IS_TMC(E7)
|
||||||
tmc_status(stepperE7, i);
|
tmc_status(stepperE7, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
static void drv_status_loop(
|
static void drv_status_loop(const TMC_drv_status_enum n, LOGICAL_AXIS_ARGS(const bool)) {
|
||||||
const TMC_drv_status_enum i,
|
if (x) {
|
||||||
LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
|
|
||||||
) {
|
|
||||||
if (print_x) {
|
|
||||||
#if AXIS_IS_TMC(X)
|
#if AXIS_IS_TMC(X)
|
||||||
tmc_parse_drv_status(stepperX, i);
|
tmc_parse_drv_status(stepperX, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(X2)
|
#if AXIS_IS_TMC(X2)
|
||||||
tmc_parse_drv_status(stepperX2, i);
|
tmc_parse_drv_status(stepperX2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
if (TERN0(HAS_Y_AXIS, y)) {
|
||||||
if (print_y) {
|
|
||||||
#if AXIS_IS_TMC(Y)
|
#if AXIS_IS_TMC(Y)
|
||||||
tmc_parse_drv_status(stepperY, i);
|
tmc_parse_drv_status(stepperY, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Y2)
|
#if AXIS_IS_TMC(Y2)
|
||||||
tmc_parse_drv_status(stepperY2, i);
|
tmc_parse_drv_status(stepperY2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (TERN0(HAS_Z_AXIS, print_z)) {
|
if (TERN0(HAS_Z_AXIS, z)) {
|
||||||
#if AXIS_IS_TMC(Z)
|
#if AXIS_IS_TMC(Z)
|
||||||
tmc_parse_drv_status(stepperZ, i);
|
tmc_parse_drv_status(stepperZ, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z2)
|
#if AXIS_IS_TMC(Z2)
|
||||||
tmc_parse_drv_status(stepperZ2, i);
|
tmc_parse_drv_status(stepperZ2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z3)
|
#if AXIS_IS_TMC(Z3)
|
||||||
tmc_parse_drv_status(stepperZ3, i);
|
tmc_parse_drv_status(stepperZ3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
tmc_parse_drv_status(stepperZ4, i);
|
tmc_parse_drv_status(stepperZ4, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (TERN0(HAS_EXTRUDERS, print_e)) {
|
#if AXIS_IS_TMC(I)
|
||||||
|
if (i) tmc_parse_drv_status(stepperI, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
if (j) tmc_parse_drv_status(stepperJ, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
if (k) tmc_parse_drv_status(stepperK, n);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (TERN0(HAS_EXTRUDERS, e)) {
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
tmc_parse_drv_status(stepperE0, i);
|
tmc_parse_drv_status(stepperE0, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E1)
|
#if AXIS_IS_TMC(E1)
|
||||||
tmc_parse_drv_status(stepperE1, i);
|
tmc_parse_drv_status(stepperE1, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E2)
|
#if AXIS_IS_TMC(E2)
|
||||||
tmc_parse_drv_status(stepperE2, i);
|
tmc_parse_drv_status(stepperE2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E3)
|
#if AXIS_IS_TMC(E3)
|
||||||
tmc_parse_drv_status(stepperE3, i);
|
tmc_parse_drv_status(stepperE3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E4)
|
#if AXIS_IS_TMC(E4)
|
||||||
tmc_parse_drv_status(stepperE4, i);
|
tmc_parse_drv_status(stepperE4, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E5)
|
#if AXIS_IS_TMC(E5)
|
||||||
tmc_parse_drv_status(stepperE5, i);
|
tmc_parse_drv_status(stepperE5, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E6)
|
#if AXIS_IS_TMC(E6)
|
||||||
tmc_parse_drv_status(stepperE6, i);
|
tmc_parse_drv_status(stepperE6, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E7)
|
#if AXIS_IS_TMC(E7)
|
||||||
tmc_parse_drv_status(stepperE7, i);
|
tmc_parse_drv_status(stepperE7, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -899,11 +924,9 @@
|
||||||
* M122 report functions
|
* M122 report functions
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void tmc_report_all(
|
void tmc_report_all(LOGICAL_AXIS_ARGS(const bool)) {
|
||||||
LOGICAL_AXIS_LIST(const bool print_e/*=true*/, const bool print_x/*=true*/, const bool print_y/*=true*/, const bool print_z/*=true*/)
|
#define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
|
||||||
) {
|
#define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
|
||||||
#define TMC_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_debug_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
|
|
||||||
#define DRV_REPORT(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); drv_status_loop(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
|
|
||||||
|
|
||||||
TMC_REPORT("\t", TMC_CODES);
|
TMC_REPORT("\t", TMC_CODES);
|
||||||
#if HAS_DRIVER(TMC2209)
|
#if HAS_DRIVER(TMC2209)
|
||||||
|
@ -1028,79 +1051,82 @@
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void tmc_get_registers(
|
static void tmc_get_registers(TMC_get_registers_enum n, LOGICAL_AXIS_ARGS(const bool)) {
|
||||||
TMC_get_registers_enum i,
|
if (x) {
|
||||||
LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
|
|
||||||
) {
|
|
||||||
if (print_x) {
|
|
||||||
#if AXIS_IS_TMC(X)
|
#if AXIS_IS_TMC(X)
|
||||||
tmc_get_registers(stepperX, i);
|
tmc_get_registers(stepperX, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(X2)
|
#if AXIS_IS_TMC(X2)
|
||||||
tmc_get_registers(stepperX2, i);
|
tmc_get_registers(stepperX2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
if (TERN0(HAS_Y_AXIS, y)) {
|
||||||
if (print_y) {
|
|
||||||
#if AXIS_IS_TMC(Y)
|
#if AXIS_IS_TMC(Y)
|
||||||
tmc_get_registers(stepperY, i);
|
tmc_get_registers(stepperY, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Y2)
|
#if AXIS_IS_TMC(Y2)
|
||||||
tmc_get_registers(stepperY2, i);
|
tmc_get_registers(stepperY2, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (TERN0(HAS_Z_AXIS, print_z)) {
|
if (TERN0(HAS_Z_AXIS, z)) {
|
||||||
#if AXIS_IS_TMC(Z)
|
#if AXIS_IS_TMC(Z)
|
||||||
tmc_get_registers(stepperZ, i);
|
tmc_get_registers(stepperZ, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z2)
|
#if AXIS_IS_TMC(Z2)
|
||||||
tmc_get_registers(stepperZ2, i);
|
tmc_get_registers(stepperZ2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z3)
|
#if AXIS_IS_TMC(Z3)
|
||||||
tmc_get_registers(stepperZ3, i);
|
tmc_get_registers(stepperZ3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
tmc_get_registers(stepperZ4, i);
|
tmc_get_registers(stepperZ4, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (TERN0(HAS_EXTRUDERS, print_e)) {
|
#if AXIS_IS_TMC(I)
|
||||||
|
if (i) tmc_get_registers(stepperI, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
if (j) tmc_get_registers(stepperJ, n);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
if (k) tmc_get_registers(stepperK, n);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (TERN0(HAS_EXTRUDERS, e)) {
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
tmc_get_registers(stepperE0, i);
|
tmc_get_registers(stepperE0, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E1)
|
#if AXIS_IS_TMC(E1)
|
||||||
tmc_get_registers(stepperE1, i);
|
tmc_get_registers(stepperE1, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E2)
|
#if AXIS_IS_TMC(E2)
|
||||||
tmc_get_registers(stepperE2, i);
|
tmc_get_registers(stepperE2, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E3)
|
#if AXIS_IS_TMC(E3)
|
||||||
tmc_get_registers(stepperE3, i);
|
tmc_get_registers(stepperE3, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E4)
|
#if AXIS_IS_TMC(E4)
|
||||||
tmc_get_registers(stepperE4, i);
|
tmc_get_registers(stepperE4, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E5)
|
#if AXIS_IS_TMC(E5)
|
||||||
tmc_get_registers(stepperE5, i);
|
tmc_get_registers(stepperE5, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E6)
|
#if AXIS_IS_TMC(E6)
|
||||||
tmc_get_registers(stepperE6, i);
|
tmc_get_registers(stepperE6, n);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_TMC(E7)
|
#if AXIS_IS_TMC(E7)
|
||||||
tmc_get_registers(stepperE7, i);
|
tmc_get_registers(stepperE7, n);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
void tmc_get_registers(
|
void tmc_get_registers(LOGICAL_AXIS_ARGS(bool)) {
|
||||||
LOGICAL_AXIS_LIST(bool print_e, bool print_x, bool print_y, bool print_z)
|
#define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_ARGS()); }while(0)
|
||||||
) {
|
|
||||||
#define _TMC_GET_REG(LABEL, ITEM) do{ SERIAL_ECHOPGM(LABEL); tmc_get_registers(ITEM, LOGICAL_AXIS_LIST(print_e, print_x, print_y, print_z)); }while(0)
|
|
||||||
#define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME)
|
#define TMC_GET_REG(NAME, TABS) _TMC_GET_REG(STRINGIFY(NAME) TABS, TMC_GET_##NAME)
|
||||||
_TMC_GET_REG("\t", TMC_AXIS_CODES);
|
_TMC_GET_REG("\t", TMC_AXIS_CODES);
|
||||||
TMC_GET_REG(GCONF, "\t\t");
|
TMC_GET_REG(GCONF, "\t\t");
|
||||||
|
@ -1185,6 +1211,15 @@
|
||||||
#if AXIS_HAS_SPI(Z4)
|
#if AXIS_HAS_SPI(Z4)
|
||||||
SET_CS_PIN(Z4);
|
SET_CS_PIN(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(I)
|
||||||
|
SET_CS_PIN(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(J)
|
||||||
|
SET_CS_PIN(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(K)
|
||||||
|
SET_CS_PIN(K);
|
||||||
|
#endif
|
||||||
#if AXIS_HAS_SPI(E0)
|
#if AXIS_HAS_SPI(E0)
|
||||||
SET_CS_PIN(E0);
|
SET_CS_PIN(E0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1234,12 +1269,10 @@ static bool test_connection(TMC &st) {
|
||||||
return test_result;
|
return test_result;
|
||||||
}
|
}
|
||||||
|
|
||||||
void test_tmc_connection(
|
void test_tmc_connection(LOGICAL_AXIS_ARGS(const bool)) {
|
||||||
LOGICAL_AXIS_LIST(const bool test_e/*=true*/, const bool test_x/*=true*/, const bool test_y/*=true*/, const bool test_z/*=true*/)
|
|
||||||
) {
|
|
||||||
uint8_t axis_connection = 0;
|
uint8_t axis_connection = 0;
|
||||||
|
|
||||||
if (test_x) {
|
if (x) {
|
||||||
#if AXIS_IS_TMC(X)
|
#if AXIS_IS_TMC(X)
|
||||||
axis_connection += test_connection(stepperX);
|
axis_connection += test_connection(stepperX);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1248,8 +1281,7 @@ void test_tmc_connection(
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
if (TERN0(HAS_Y_AXIS, y)) {
|
||||||
if (test_y) {
|
|
||||||
#if AXIS_IS_TMC(Y)
|
#if AXIS_IS_TMC(Y)
|
||||||
axis_connection += test_connection(stepperY);
|
axis_connection += test_connection(stepperY);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1257,9 +1289,8 @@ void test_tmc_connection(
|
||||||
axis_connection += test_connection(stepperY2);
|
axis_connection += test_connection(stepperY2);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (TERN0(HAS_Z_AXIS, test_z)) {
|
if (TERN0(HAS_Z_AXIS, z)) {
|
||||||
#if AXIS_IS_TMC(Z)
|
#if AXIS_IS_TMC(Z)
|
||||||
axis_connection += test_connection(stepperZ);
|
axis_connection += test_connection(stepperZ);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1274,7 +1305,17 @@ void test_tmc_connection(
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (TERN0(HAS_EXTRUDERS, test_e)) {
|
#if AXIS_IS_TMC(I)
|
||||||
|
if (i) axis_connection += test_connection(stepperI);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
if (j) axis_connection += test_connection(stepperJ);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
if (k) axis_connection += test_connection(stepperK);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (TERN0(HAS_EXTRUDERS, e)) {
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
axis_connection += test_connection(stepperE0);
|
axis_connection += test_connection(stepperE0);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -335,20 +335,14 @@ void tmc_print_current(TMC &st) {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void monitor_tmc_drivers();
|
void monitor_tmc_drivers();
|
||||||
void test_tmc_connection(
|
void test_tmc_connection(LOGICAL_AXIS_DECL(const bool, true));
|
||||||
LOGICAL_AXIS_LIST(const bool test_e=true, const bool test_x=true, const bool test_y=true, const bool test_z=true)
|
|
||||||
);
|
|
||||||
|
|
||||||
#if ENABLED(TMC_DEBUG)
|
#if ENABLED(TMC_DEBUG)
|
||||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
void tmc_set_report_interval(const uint16_t update_interval);
|
void tmc_set_report_interval(const uint16_t update_interval);
|
||||||
#endif
|
#endif
|
||||||
void tmc_report_all(
|
void tmc_report_all(LOGICAL_AXIS_DECL(const bool, true));
|
||||||
LOGICAL_AXIS_LIST(const bool print_e=true, const bool print_x=true, const bool print_y=true, const bool print_z=true)
|
void tmc_get_registers(LOGICAL_AXIS_ARGS(const bool));
|
||||||
);
|
|
||||||
void tmc_get_registers(
|
|
||||||
LOGICAL_AXIS_LIST(const bool print_e, const bool print_x, const bool print_y, const bool print_z)
|
|
||||||
);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -361,7 +355,7 @@ void test_tmc_connection(
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
|
|
||||||
// Track enabled status of stealthChop and only re-enable where applicable
|
// Track enabled status of stealthChop and only re-enable where applicable
|
||||||
struct sensorless_t { bool LINEAR_AXIS_LIST(x, y, z), x2, y2, z2, z3, z4; };
|
struct sensorless_t { bool LINEAR_AXIS_ARGS(), x2, y2, z2, z3, z4; };
|
||||||
|
|
||||||
#if ENABLED(IMPROVE_HOMING_RELIABILITY)
|
#if ENABLED(IMPROVE_HOMING_RELIABILITY)
|
||||||
extern millis_t sg_guard_period;
|
extern millis_t sg_guard_period;
|
||||||
|
|
|
@ -689,7 +689,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||||
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1)));
|
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1)));
|
||||||
|
|
||||||
// Retain the last probe position
|
// Retain the last probe position
|
||||||
abl.probePos = points[i];
|
abl.probePos = xy_pos_t(points[i]);
|
||||||
abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level);
|
abl.measured_z = faux ? 0.001 * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level);
|
||||||
if (isnan(abl.measured_z)) {
|
if (isnan(abl.measured_z)) {
|
||||||
set_bed_leveling_enabled(abl.reenable);
|
set_bed_leveling_enabled(abl.reenable);
|
||||||
|
@ -795,7 +795,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||||
const int ind = abl.indexIntoAB[xx][yy];
|
const int ind = abl.indexIntoAB[xx][yy];
|
||||||
xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points],
|
xyz_float_t tmp = { abl.eqnAMatrix[ind + 0 * abl.abl_points],
|
||||||
abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 };
|
abl.eqnAMatrix[ind + 1 * abl.abl_points], 0 };
|
||||||
planner.bed_level_matrix.apply_rotation_xyz(tmp);
|
planner.bed_level_matrix.apply_rotation_xyz(tmp.x, tmp.y, tmp.z);
|
||||||
if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z);
|
if (get_min) NOMORE(min_diff, abl.eqnBVector[ind] - tmp.z);
|
||||||
const float subval = get_min ? abl.mean : tmp.z + min_diff,
|
const float subval = get_min ? abl.mean : tmp.z + min_diff,
|
||||||
diff = abl.eqnBVector[ind] - subval;
|
diff = abl.eqnBVector[ind] - subval;
|
||||||
|
|
|
@ -323,42 +323,44 @@ void GcodeSuite::G28() {
|
||||||
|
|
||||||
#define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS))))
|
#define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS))))
|
||||||
|
|
||||||
const bool homeZ = parser.seen_test('Z'),
|
const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')),
|
||||||
LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing
|
LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing
|
||||||
needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false // UNUSED
|
needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED
|
||||||
|
needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K)
|
||||||
),
|
),
|
||||||
LINEAR_AXIS_LIST( // Home each axis if needed or flagged
|
LINEAR_AXIS_LIST( // Home each axis if needed or flagged
|
||||||
homeX = needX || parser.seen_test('X'),
|
homeX = needX || parser.seen_test('X'),
|
||||||
homeY = needY || parser.seen_test('Y'),
|
homeY = needY || parser.seen_test('Y'),
|
||||||
homeZZ = homeZ // UNUSED
|
homeZZ = homeZ,
|
||||||
|
homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME),
|
||||||
),
|
),
|
||||||
// Home-all if all or none are flagged
|
home_all = LINEAR_AXIS_GANG( // Home-all if all or none are flagged
|
||||||
home_all = true LINEAR_AXIS_GANG(&& homeX == homeX, && homeX == homeY, && homeX == homeZ),
|
homeX == homeX, && homeY == homeX, && homeZ == homeX,
|
||||||
LINEAR_AXIS_LIST(doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ);
|
&& homeI == homeX, && homeJ == homeX, && homeK == homeX
|
||||||
|
),
|
||||||
UNUSED(needZ);
|
LINEAR_AXIS_LIST(
|
||||||
UNUSED(homeZZ);
|
doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ,
|
||||||
|
doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK
|
||||||
#if ENABLED(HOME_Z_FIRST)
|
);
|
||||||
|
|
||||||
if (doZ) homeaxis(Z_AXIS);
|
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
UNUSED(needZ); UNUSED(homeZZ);
|
||||||
|
#else
|
||||||
|
constexpr bool doZ = false;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS));
|
||||||
|
|
||||||
const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT;
|
const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT;
|
||||||
|
|
||||||
if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ)))) {
|
if (z_homing_height && (0 LINEAR_AXIS_GANG(|| doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) {
|
||||||
// Raise Z before homing any other axes and z is not already high enough (never lower z)
|
// Raise Z before homing any other axes and z is not already high enough (never lower z)
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height);
|
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height);
|
||||||
do_z_clearance(z_homing_height);
|
do_z_clearance(z_homing_height);
|
||||||
TERN_(BLTOUCH, bltouch.init());
|
TERN_(BLTOUCH, bltouch.init());
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(QUICK_HOME)
|
TERN_(QUICK_HOME, if (doX && doY) quick_home_xy());
|
||||||
|
|
||||||
if (doX && doY) quick_home_xy();
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Home Y (before X)
|
// Home Y (before X)
|
||||||
if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX)))
|
if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX)))
|
||||||
|
@ -397,7 +399,7 @@ void GcodeSuite::G28() {
|
||||||
TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
|
TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(slow_homing));
|
||||||
|
|
||||||
// Home Z last if homing towards the bed
|
// Home Z last if homing towards the bed
|
||||||
#if DISABLED(HOME_Z_FIRST)
|
#if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
|
||||||
if (doZ) {
|
if (doZ) {
|
||||||
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
|
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
|
||||||
stepper.set_all_z_lock(false);
|
stepper.set_all_z_lock(false);
|
||||||
|
@ -409,6 +411,16 @@ void GcodeSuite::G28() {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
if (doI) homeaxis(I_AXIS);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
if (doJ) homeaxis(J_AXIS);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
if (doK) homeaxis(K_AXIS);
|
||||||
|
#endif
|
||||||
|
|
||||||
sync_plan_position();
|
sync_plan_position();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -480,6 +492,15 @@ void GcodeSuite::G28() {
|
||||||
#if HAS_CURRENT_HOME(Y2)
|
#if HAS_CURRENT_HOME(Y2)
|
||||||
stepperY2.rms_current(tmc_save_current_Y2);
|
stepperY2.rms_current(tmc_save_current_Y2);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_CURRENT_HOME(I)
|
||||||
|
stepperI.rms_current(tmc_save_current_I);
|
||||||
|
#endif
|
||||||
|
#if HAS_CURRENT_HOME(J)
|
||||||
|
stepperJ.rms_current(tmc_save_current_J);
|
||||||
|
#endif
|
||||||
|
#if HAS_CURRENT_HOME(K)
|
||||||
|
stepperK.rms_current(tmc_save_current_K);
|
||||||
|
#endif
|
||||||
#endif // HAS_HOMING_CURRENT
|
#endif // HAS_HOMING_CURRENT
|
||||||
|
|
||||||
ui.refresh();
|
ui.refresh();
|
||||||
|
@ -498,11 +519,13 @@ void GcodeSuite::G28() {
|
||||||
// Set L6470 absolute position registers to counts
|
// Set L6470 absolute position registers to counts
|
||||||
// constexpr *might* move this to PROGMEM.
|
// constexpr *might* move this to PROGMEM.
|
||||||
// If not, this will need a PROGMEM directive and an accessor.
|
// If not, this will need a PROGMEM directive and an accessor.
|
||||||
|
#define _EN_ITEM(N) , E_AXIS
|
||||||
static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
|
static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
|
||||||
X_AXIS, Y_AXIS, Z_AXIS,
|
LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS),
|
||||||
X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS,
|
X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS
|
||||||
E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS, E_AXIS
|
REPEAT(E_STEPPERS, _EN_ITEM)
|
||||||
};
|
};
|
||||||
|
#undef _EN_ITEM
|
||||||
for (uint8_t j = 1; j <= L64XX::chain[0]; j++) {
|
for (uint8_t j = 1; j <= L64XX::chain[0]; j++) {
|
||||||
const uint8_t cv = L64XX::chain[j];
|
const uint8_t cv = L64XX::chain[j];
|
||||||
L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv]));
|
L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv]));
|
||||||
|
|
|
@ -73,11 +73,23 @@
|
||||||
#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT)
|
#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT)
|
||||||
#define HAS_X_CENTER 1
|
#define HAS_X_CENTER 1
|
||||||
#endif
|
#endif
|
||||||
#if BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
|
#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
|
||||||
#define HAS_Y_CENTER 1
|
#define HAS_Y_CENTER 1
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX)
|
||||||
|
#define HAS_I_CENTER 1
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX)
|
||||||
|
#define HAS_J_CENTER 1
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX)
|
||||||
|
#define HAS_K_CENTER 1
|
||||||
|
#endif
|
||||||
|
|
||||||
enum side_t : uint8_t { TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES };
|
enum side_t : uint8_t {
|
||||||
|
TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES,
|
||||||
|
LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM)
|
||||||
|
};
|
||||||
|
|
||||||
static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER;
|
static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER;
|
||||||
static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS;
|
static constexpr xyz_float_t dimensions CALIBRATION_OBJECT_DIMENSIONS;
|
||||||
|
@ -105,7 +117,7 @@ struct measurements_t {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
inline void calibration_move() {
|
inline void calibration_move() {
|
||||||
do_blocking_move_to(current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
|
do_blocking_move_to((xyz_pos_t)current_position, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -174,7 +186,7 @@ float measuring_movement(const AxisEnum axis, const int dir, const bool stop_sta
|
||||||
destination = current_position;
|
destination = current_position;
|
||||||
for (float travel = 0; travel < limit; travel += step) {
|
for (float travel = 0; travel < limit; travel += step) {
|
||||||
destination[axis] += dir * step;
|
destination[axis] += dir * step;
|
||||||
do_blocking_move_to(destination, mms);
|
do_blocking_move_to((xyz_pos_t)destination, mms);
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
if (read_calibration_pin() == stop_state) break;
|
if (read_calibration_pin() == stop_state) break;
|
||||||
}
|
}
|
||||||
|
@ -209,7 +221,7 @@ inline float measure(const AxisEnum axis, const int dir, const bool stop_state,
|
||||||
// Move back to the starting position
|
// Move back to the starting position
|
||||||
destination = current_position;
|
destination = current_position;
|
||||||
destination[axis] = start_pos;
|
destination[axis] = start_pos;
|
||||||
do_blocking_move_to(destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
|
do_blocking_move_to((xyz_pos_t)destination, MMM_TO_MMS(CALIBRATION_FEEDRATE_TRAVEL));
|
||||||
return measured_pos;
|
return measured_pos;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -230,7 +242,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
|
||||||
park_above_object(m, uncertainty);
|
park_above_object(m, uncertainty);
|
||||||
|
|
||||||
switch (side) {
|
switch (side) {
|
||||||
#if AXIS_CAN_CALIBRATE(Z)
|
#if AXIS_CAN_CALIBRATE(X)
|
||||||
|
case RIGHT: dir = -1;
|
||||||
|
case LEFT: axis = X_AXIS; break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y)
|
||||||
|
case BACK: dir = -1;
|
||||||
|
case FRONT: axis = Y_AXIS; break;
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||||
case TOP: {
|
case TOP: {
|
||||||
const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty);
|
const float measurement = measure(Z_AXIS, -1, true, &m.backlash[TOP], uncertainty);
|
||||||
m.obj_center.z = measurement - dimensions.z / 2;
|
m.obj_center.z = measurement - dimensions.z / 2;
|
||||||
|
@ -238,13 +258,17 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_CAN_CALIBRATE(X)
|
#if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I)
|
||||||
case RIGHT: dir = -1;
|
case IMINIMUM: dir = -1;
|
||||||
case LEFT: axis = X_AXIS; break;
|
case IMAXIMUM: axis = I_AXIS; break;
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_CAN_CALIBRATE(Y)
|
#if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J)
|
||||||
case BACK: dir = -1;
|
case JMINIMUM: dir = -1;
|
||||||
case FRONT: axis = Y_AXIS; break;
|
case JMAXIMUM: axis = J_AXIS; break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K)
|
||||||
|
case KMINIMUM: dir = -1;
|
||||||
|
case KMAXIMUM: axis = K_AXIS; break;
|
||||||
#endif
|
#endif
|
||||||
default: return;
|
default: return;
|
||||||
}
|
}
|
||||||
|
@ -293,10 +317,19 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge));
|
TERN_(CALIBRATION_MEASURE_FRONT, probe_side(m, uncertainty, FRONT, probe_top_at_edge));
|
||||||
TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge));
|
TERN_(CALIBRATION_MEASURE_LEFT, probe_side(m, uncertainty, LEFT, probe_top_at_edge));
|
||||||
TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge));
|
TERN_(CALIBRATION_MEASURE_BACK, probe_side(m, uncertainty, BACK, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_IMIN, probe_side(m, uncertainty, IMINIMUM, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_IMAX, probe_side(m, uncertainty, IMAXIMUM, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_JMIN, probe_side(m, uncertainty, JMINIMUM, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_JMAX, probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_KMIN, probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge));
|
||||||
|
TERN_(CALIBRATION_MEASURE_KMAX, probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge));
|
||||||
|
|
||||||
// Compute the measured center of the calibration object.
|
// Compute the measured center of the calibration object.
|
||||||
TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2);
|
TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2);
|
||||||
TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2);
|
TERN_(HAS_Y_CENTER, m.obj_center.y = (m.obj_side[FRONT] + m.obj_side[BACK]) / 2);
|
||||||
|
TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2);
|
||||||
|
TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2);
|
||||||
|
TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2);
|
||||||
|
|
||||||
// Compute the outside diameter of the nozzle at the height
|
// Compute the outside diameter of the nozzle at the height
|
||||||
// at which it makes contact with the calibration object
|
// at which it makes contact with the calibration object
|
||||||
|
@ -310,14 +343,17 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x),
|
m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x),
|
||||||
m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y),
|
m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y),
|
||||||
m.pos_error.z = true_center.z - m.obj_center.z
|
m.pos_error.z = true_center.z - m.obj_center.z,
|
||||||
|
m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i),
|
||||||
|
m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j),
|
||||||
|
m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k)
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(CALIBRATION_REPORTING)
|
#if ENABLED(CALIBRATION_REPORTING)
|
||||||
inline void report_measured_faces(const measurements_t &m) {
|
inline void report_measured_faces(const measurements_t &m) {
|
||||||
SERIAL_ECHOLNPGM("Sides:");
|
SERIAL_ECHOLNPGM("Sides:");
|
||||||
#if AXIS_CAN_CALIBRATE(Z)
|
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||||
SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]);
|
SERIAL_ECHOLNPAIR(" Top: ", m.obj_side[TOP]);
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(CALIBRATION_MEASURE_LEFT)
|
#if ENABLED(CALIBRATION_MEASURE_LEFT)
|
||||||
|
@ -326,12 +362,38 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
#if ENABLED(CALIBRATION_MEASURE_RIGHT)
|
#if ENABLED(CALIBRATION_MEASURE_RIGHT)
|
||||||
SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]);
|
SERIAL_ECHOLNPAIR(" Right: ", m.obj_side[RIGHT]);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_Y_AXIS
|
||||||
#if ENABLED(CALIBRATION_MEASURE_FRONT)
|
#if ENABLED(CALIBRATION_MEASURE_FRONT)
|
||||||
SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]);
|
SERIAL_ECHOLNPAIR(" Front: ", m.obj_side[FRONT]);
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(CALIBRATION_MEASURE_BACK)
|
#if ENABLED(CALIBRATION_MEASURE_BACK)
|
||||||
SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]);
|
SERIAL_ECHOLNPAIR(" Back: ", m.obj_side[BACK]);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_IMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_JMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_KMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -344,6 +406,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y);
|
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.obj_center.y);
|
||||||
#endif
|
#endif
|
||||||
SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z);
|
SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.obj_center.z);
|
||||||
|
#if HAS_I_CENTER
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_I_STR, m.obj_center.i);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_CENTER
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_J_STR, m.obj_center.j);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_CENTER
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_K_STR, m.obj_center.k);
|
||||||
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -357,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]);
|
SERIAL_ECHOLNPAIR(" Right: ", m.backlash[RIGHT]);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_CAN_CALIBRATE(Y)
|
#if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y)
|
||||||
#if ENABLED(CALIBRATION_MEASURE_FRONT)
|
#if ENABLED(CALIBRATION_MEASURE_FRONT)
|
||||||
SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]);
|
SERIAL_ECHOLNPAIR(" Front: ", m.backlash[FRONT]);
|
||||||
#endif
|
#endif
|
||||||
|
@ -365,9 +436,33 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]);
|
SERIAL_ECHOLNPAIR(" Back: ", m.backlash[BACK]);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_CAN_CALIBRATE(Z)
|
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||||
SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]);
|
SERIAL_ECHOLNPAIR(" Top: ", m.backlash[TOP]);
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 AXIS_CAN_CALIBRATE(I)
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_I_MIN ": ", m.backlash[IMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_IMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 AXIS_CAN_CALIBRATE(J)
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_J_MIN ": ", m.backlash[JMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_JMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 AXIS_CAN_CALIBRATE(K)
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_K_MIN ": ", m.backlash[KMINIMUM]);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(CALIBRATION_MEASURE_KMAX)
|
||||||
|
SERIAL_ECHOLNPAIR(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -375,29 +470,37 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||||
SERIAL_CHAR('T');
|
SERIAL_CHAR('T');
|
||||||
SERIAL_ECHO(active_extruder);
|
SERIAL_ECHO(active_extruder);
|
||||||
SERIAL_ECHOLNPGM(" Positional Error:");
|
SERIAL_ECHOLNPGM(" Positional Error:");
|
||||||
#if HAS_X_CENTER
|
#if HAS_X_CENTER && AXIS_CAN_CALIBRATE(X)
|
||||||
SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x);
|
SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Y_CENTER
|
#if HAS_Y_CENTER && AXIS_CAN_CALIBRATE(Y)
|
||||||
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y);
|
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.pos_error.y);
|
||||||
#endif
|
#endif
|
||||||
if (AXIS_CAN_CALIBRATE(Z)) SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
|
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
|
||||||
|
#endif
|
||||||
|
#if HAS_I_CENTER && AXIS_CAN_CALIBRATE(I)
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_I_STR, m.pos_error.i);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_CENTER && AXIS_CAN_CALIBRATE(J)
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_J_STR, m.pos_error.j);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K)
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_Z_STR, m.pos_error.z);
|
||||||
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void report_measured_nozzle_dimensions(const measurements_t &m) {
|
inline void report_measured_nozzle_dimensions(const measurements_t &m) {
|
||||||
SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:");
|
SERIAL_ECHOLNPGM("Nozzle Tip Outer Dimensions:");
|
||||||
#if HAS_X_CENTER || HAS_Y_CENTER
|
|
||||||
#if HAS_X_CENTER
|
#if HAS_X_CENTER
|
||||||
SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x);
|
SERIAL_ECHOLNPAIR_P(SP_X_STR, m.nozzle_outer_dimension.x);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Y_CENTER
|
#if HAS_Y_CENTER
|
||||||
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y);
|
SERIAL_ECHOLNPAIR_P(SP_Y_STR, m.nozzle_outer_dimension.y);
|
||||||
#endif
|
#endif
|
||||||
#else
|
|
||||||
UNUSED(m);
|
|
||||||
#endif
|
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
|
UNUSED(m);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAS_HOTEND_OFFSET
|
#if HAS_HOTEND_OFFSET
|
||||||
|
@ -446,8 +549,33 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
|
||||||
backlash.distance_mm.y = m.backlash[BACK];
|
backlash.distance_mm.y = m.backlash[BACK];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP];
|
TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]);
|
||||||
|
|
||||||
|
#if HAS_I_CENTER
|
||||||
|
backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2;
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||||
|
backlash.distance_mm.i = m.backlash[IMINIMUM];
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_IMAX)
|
||||||
|
backlash.distance_mm.i = m.backlash[IMAXIMUM];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_CENTER
|
||||||
|
backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2;
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||||
|
backlash.distance_mm.j = m.backlash[JMINIMUM];
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_JMAX)
|
||||||
|
backlash.distance_mm.j = m.backlash[JMAXIMUM];
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_CENTER
|
||||||
|
backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2;
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||||
|
backlash.distance_mm.k = m.backlash[KMINIMUM];
|
||||||
|
#elif ENABLED(CALIBRATION_MEASURE_KMAX)
|
||||||
|
backlash.distance_mm.k = m.backlash[KMAXIMUM];
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // BACKLASH_GCODE
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(BACKLASH_GCODE)
|
#if ENABLED(BACKLASH_GCODE)
|
||||||
|
@ -458,7 +586,8 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
|
||||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||||
const xyz_float_t move = LINEAR_AXIS_ARRAY(
|
const xyz_float_t move = LINEAR_AXIS_ARRAY(
|
||||||
AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3
|
AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3,
|
||||||
|
AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3
|
||||||
);
|
);
|
||||||
current_position += move; calibration_move();
|
current_position += move; calibration_move();
|
||||||
current_position -= move; calibration_move();
|
current_position -= move; calibration_move();
|
||||||
|
@ -487,11 +616,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
|
||||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||||
|
|
||||||
#if HAS_MULTI_HOTEND
|
TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder));
|
||||||
set_nozzle(m, extruder);
|
|
||||||
#else
|
|
||||||
UNUSED(extruder);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
probe_sides(m, uncertainty);
|
probe_sides(m, uncertainty);
|
||||||
|
|
||||||
|
@ -510,6 +635,10 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
|
||||||
if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS);
|
if (ENABLED(HAS_Y_CENTER) && AXIS_CAN_CALIBRATE(Y)) update_measurements(m, Y_AXIS);
|
||||||
if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS);
|
if (AXIS_CAN_CALIBRATE(Z)) update_measurements(m, Z_AXIS);
|
||||||
|
|
||||||
|
TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS));
|
||||||
|
TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS));
|
||||||
|
TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS));
|
||||||
|
|
||||||
sync_plan_position();
|
sync_plan_position();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -52,7 +52,10 @@ void GcodeSuite::M425() {
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
case X_AXIS: return AXIS_CAN_CALIBRATE(X),
|
case X_AXIS: return AXIS_CAN_CALIBRATE(X),
|
||||||
case Y_AXIS: return AXIS_CAN_CALIBRATE(Y),
|
case Y_AXIS: return AXIS_CAN_CALIBRATE(Y),
|
||||||
case Z_AXIS: return AXIS_CAN_CALIBRATE(Z)
|
case Z_AXIS: return AXIS_CAN_CALIBRATE(Z),
|
||||||
|
case I_AXIS: return AXIS_CAN_CALIBRATE(I),
|
||||||
|
case J_AXIS: return AXIS_CAN_CALIBRATE(J),
|
||||||
|
case K_AXIS: return AXIS_CAN_CALIBRATE(K),
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
|
@ -154,6 +154,9 @@ void GcodeSuite::M205() {
|
||||||
if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
|
if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
|
||||||
if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
|
if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
|
||||||
#if HAS_JUNCTION_DEVIATION
|
#if HAS_JUNCTION_DEVIATION
|
||||||
|
#if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J')
|
||||||
|
#error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation."
|
||||||
|
#endif
|
||||||
if (parser.seenval('J')) {
|
if (parser.seenval('J')) {
|
||||||
const float junc_dev = parser.value_linear_units();
|
const float junc_dev = parser.value_linear_units();
|
||||||
if (WITHIN(junc_dev, 0.01f, 0.3f)) {
|
if (WITHIN(junc_dev, 0.01f, 0.3f)) {
|
||||||
|
@ -170,7 +173,10 @@ void GcodeSuite::M205() {
|
||||||
if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()),
|
if (parser.seenval('E')) planner.set_max_jerk(E_AXIS, parser.value_linear_units()),
|
||||||
if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()),
|
if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()),
|
||||||
if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()),
|
if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()),
|
||||||
if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units())
|
if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()),
|
||||||
|
if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()),
|
||||||
|
if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()),
|
||||||
|
if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units())
|
||||||
);
|
);
|
||||||
#if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
|
#if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
|
||||||
if (seenZ && planner.max_jerk.z <= 0.1f)
|
if (seenZ && planner.max_jerk.z <= 0.1f)
|
||||||
|
|
|
@ -28,8 +28,11 @@ void report_M92(const bool echo=true, const int8_t e=-1) {
|
||||||
SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES),
|
SERIAL_ECHOPAIR_P(LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]),
|
PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]),
|
||||||
SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]),
|
SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]),
|
||||||
SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS])
|
SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]),
|
||||||
));
|
SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
|
||||||
|
SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
|
||||||
|
SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]))
|
||||||
|
);
|
||||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||||
SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS]));
|
SERIAL_ECHOPAIR_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS]));
|
||||||
#endif
|
#endif
|
||||||
|
@ -67,7 +70,7 @@ void GcodeSuite::M92() {
|
||||||
|
|
||||||
// No arguments? Show M92 report.
|
// No arguments? Show M92 report.
|
||||||
if (!parser.seen(
|
if (!parser.seen(
|
||||||
LOGICAL_AXIS_GANG("E", "X", "Y", "Z")
|
LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)
|
||||||
TERN_(MAGIC_NUMBERS_GCODE, "HL")
|
TERN_(MAGIC_NUMBERS_GCODE, "HL")
|
||||||
)) return report_M92(true, target_extruder);
|
)) return report_M92(true, target_extruder);
|
||||||
|
|
||||||
|
|
|
@ -33,12 +33,15 @@
|
||||||
* M17: Enable stepper motors
|
* M17: Enable stepper motors
|
||||||
*/
|
*/
|
||||||
void GcodeSuite::M17() {
|
void GcodeSuite::M17() {
|
||||||
if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) {
|
if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
|
||||||
LOGICAL_AXIS_CODE(
|
LOGICAL_AXIS_CODE(
|
||||||
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(),
|
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) enable_e_steppers(),
|
||||||
if (parser.seen_test('X')) ENABLE_AXIS_X(),
|
if (parser.seen_test('X')) ENABLE_AXIS_X(),
|
||||||
if (parser.seen_test('Y')) ENABLE_AXIS_Y(),
|
if (parser.seen_test('Y')) ENABLE_AXIS_Y(),
|
||||||
if (parser.seen_test('Z')) ENABLE_AXIS_Z()
|
if (parser.seen_test('Z')) ENABLE_AXIS_Z(),
|
||||||
|
if (parser.seen_test(AXIS4_NAME)) ENABLE_AXIS_I(),
|
||||||
|
if (parser.seen_test(AXIS5_NAME)) ENABLE_AXIS_J(),
|
||||||
|
if (parser.seen_test(AXIS6_NAME)) ENABLE_AXIS_K()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -56,13 +59,16 @@ void GcodeSuite::M18_M84() {
|
||||||
stepper_inactive_time = parser.value_millis_from_seconds();
|
stepper_inactive_time = parser.value_millis_from_seconds();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"))) {
|
if (parser.seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
LOGICAL_AXIS_CODE(
|
LOGICAL_AXIS_CODE(
|
||||||
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(),
|
if (TERN0(HAS_E_STEPPER_ENABLE, parser.seen_test('E'))) disable_e_steppers(),
|
||||||
if (parser.seen_test('X')) DISABLE_AXIS_X(),
|
if (parser.seen_test('X')) DISABLE_AXIS_X(),
|
||||||
if (parser.seen_test('Y')) DISABLE_AXIS_Y(),
|
if (parser.seen_test('Y')) DISABLE_AXIS_Y(),
|
||||||
if (parser.seen_test('Z')) DISABLE_AXIS_Z()
|
if (parser.seen_test('Z')) DISABLE_AXIS_Z(),
|
||||||
|
if (parser.seen_test(AXIS4_NAME)) DISABLE_AXIS_I(),
|
||||||
|
if (parser.seen_test(AXIS5_NAME)) DISABLE_AXIS_J(),
|
||||||
|
if (parser.seen_test(AXIS6_NAME)) DISABLE_AXIS_K()
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
|
|
|
@ -70,26 +70,12 @@
|
||||||
dual_x_carriage_mode = (DualXMode)parser.value_byte();
|
dual_x_carriage_mode = (DualXMode)parser.value_byte();
|
||||||
idex_set_mirrored_mode(false);
|
idex_set_mirrored_mode(false);
|
||||||
|
|
||||||
if (dual_x_carriage_mode == DXC_MIRRORED_MODE) {
|
|
||||||
if (previous_mode != DXC_DUPLICATION_MODE) {
|
|
||||||
SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to ");
|
|
||||||
SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE.");
|
|
||||||
dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
idex_set_mirrored_mode(true);
|
|
||||||
float x_jog = current_position.x - .1;
|
|
||||||
for (uint8_t i = 2; --i;) {
|
|
||||||
planner.buffer_line(x_jog, current_position.y, current_position.z, current_position.e, feedrate_mm_s, 0);
|
|
||||||
x_jog += .1;
|
|
||||||
}
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (dual_x_carriage_mode) {
|
switch (dual_x_carriage_mode) {
|
||||||
|
|
||||||
case DXC_FULL_CONTROL_MODE:
|
case DXC_FULL_CONTROL_MODE:
|
||||||
case DXC_AUTO_PARK_MODE:
|
case DXC_AUTO_PARK_MODE:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case DXC_DUPLICATION_MODE:
|
case DXC_DUPLICATION_MODE:
|
||||||
// Set the X offset, but no less than the safety gap
|
// Set the X offset, but no less than the safety gap
|
||||||
if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
|
if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
|
||||||
|
@ -97,10 +83,29 @@
|
||||||
// Always switch back to tool 0
|
// Always switch back to tool 0
|
||||||
if (active_extruder != 0) tool_change(0);
|
if (active_extruder != 0) tool_change(0);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case DXC_MIRRORED_MODE: {
|
||||||
|
if (previous_mode != DXC_DUPLICATION_MODE) {
|
||||||
|
SERIAL_ECHOLNPGM("Printer must be in DXC_DUPLICATION_MODE prior to ");
|
||||||
|
SERIAL_ECHOLNPGM("specifying DXC_MIRRORED_MODE.");
|
||||||
|
dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
idex_set_mirrored_mode(true);
|
||||||
|
|
||||||
|
// Do a small 'jog' motion in the X axis
|
||||||
|
xyze_pos_t dest = current_position; dest.x -= 0.1f;
|
||||||
|
for (uint8_t i = 2; --i;) {
|
||||||
|
planner.buffer_line(dest, feedrate_mm_s, 0);
|
||||||
|
dest.x += 0.1f;
|
||||||
|
}
|
||||||
|
} return;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
|
dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
idex_set_parked(false);
|
idex_set_parked(false);
|
||||||
set_duplication_enabled(false);
|
set_duplication_enabled(false);
|
||||||
|
|
||||||
|
|
|
@ -253,7 +253,7 @@ void GcodeSuite::M906() {
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
#if HAS_Y_AXIS
|
||||||
case Y_AXIS:
|
case Y_AXIS:
|
||||||
#if AXIS_IS_L64XX(Y)
|
#if AXIS_IS_L64XX(Y)
|
||||||
if (index == 0) L6470_SET_KVAL_HOLD(Y);
|
if (index == 0) L6470_SET_KVAL_HOLD(Y);
|
||||||
|
|
|
@ -47,12 +47,13 @@ void GcodeSuite::G60() {
|
||||||
SBI(saved_slots[slot >> 3], slot & 0x07);
|
SBI(saved_slots[slot >> 3], slot & 0x07);
|
||||||
|
|
||||||
#if ENABLED(SAVED_POSITIONS_DEBUG)
|
#if ENABLED(SAVED_POSITIONS_DEBUG)
|
||||||
const xyze_pos_t &pos = stored_position[slot];
|
|
||||||
DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot);
|
DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot);
|
||||||
DEBUG_ECHOPAIR_F(" : X", pos.x);
|
const xyze_pos_t &pos = stored_position[slot];
|
||||||
DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y);
|
DEBUG_ECHOLNPAIR_F_P(
|
||||||
DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z);
|
LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e,
|
||||||
DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e);
|
PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z,
|
||||||
|
SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k)
|
||||||
|
);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -45,7 +45,7 @@ void GcodeSuite::G61(void) {
|
||||||
|
|
||||||
const uint8_t slot = parser.byteval('S');
|
const uint8_t slot = parser.byteval('S');
|
||||||
|
|
||||||
#define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT)))
|
#define SYNC_E(POINT) TERN_(HAS_EXTRUDERS, planner.set_e_position_mm((destination.e = current_position.e = (POINT))))
|
||||||
|
|
||||||
#if SAVED_POSITIONS < 256
|
#if SAVED_POSITIONS < 256
|
||||||
if (slot >= SAVED_POSITIONS) {
|
if (slot >= SAVED_POSITIONS) {
|
||||||
|
@ -68,7 +68,7 @@ void GcodeSuite::G61(void) {
|
||||||
SYNC_E(stored_position[slot].e);
|
SYNC_E(stored_position[slot].e);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) {
|
if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
|
||||||
DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot);
|
DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot);
|
||||||
LOOP_LINEAR_AXES(i) {
|
LOOP_LINEAR_AXES(i) {
|
||||||
destination[i] = parser.seen(AXIS_CHAR(i))
|
destination[i] = parser.seen(AXIS_CHAR(i))
|
||||||
|
|
|
@ -35,7 +35,7 @@ void GcodeSuite::M122() {
|
||||||
xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false);
|
xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false);
|
||||||
|
|
||||||
bool print_all = true;
|
bool print_all = true;
|
||||||
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; }
|
LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; }
|
||||||
|
|
||||||
if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true;
|
if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true;
|
||||||
|
|
||||||
|
@ -49,21 +49,13 @@ void GcodeSuite::M122() {
|
||||||
tmc_set_report_interval(interval);
|
tmc_set_report_interval(interval);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (parser.seen_test('V')) {
|
if (parser.seen_test('V'))
|
||||||
tmc_get_registers(
|
tmc_get_registers(LOGICAL_AXIS_ELEM(print_axis));
|
||||||
LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
|
else
|
||||||
);
|
tmc_report_all(LOGICAL_AXIS_ELEM(print_axis));
|
||||||
}
|
|
||||||
else {
|
|
||||||
tmc_report_all(
|
|
||||||
LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
test_tmc_connection(
|
test_tmc_connection(LOGICAL_AXIS_ELEM(print_axis));
|
||||||
LOGICAL_AXIS_LIST(print_axis.e, print_axis.x, print_axis.y, print_axis.z)
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAS_TRINAMIC_CONFIG
|
#endif // HAS_TRINAMIC_CONFIG
|
||||||
|
|
|
@ -43,81 +43,56 @@ void tmc_set_stealthChop(TMC &st, const bool enable) {
|
||||||
static void set_stealth_status(const bool enable, const int8_t target_extruder) {
|
static void set_stealth_status(const bool enable, const int8_t target_extruder) {
|
||||||
#define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable)
|
#define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable)
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \
|
#if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \
|
||||||
|| AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \
|
|| I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \
|
||||||
|| AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) \
|
|| X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP
|
||||||
|| AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
const uint8_t index = parser.byteval('I');
|
const uint8_t index = parser.byteval('I');
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) {
|
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case X_AXIS:
|
case X_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X));
|
||||||
if (index == 0) TMC_SET_STEALTH(X);
|
TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2));
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
|
||||||
if (index == 1) TMC_SET_STEALTH(X2);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
#if HAS_Y_AXIS
|
||||||
case Y_AXIS:
|
case Y_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y));
|
||||||
if (index == 0) TMC_SET_STEALTH(Y);
|
TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2));
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
|
||||||
if (index == 1) TMC_SET_STEALTH(Y2);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_AXIS
|
#if HAS_Z_AXIS
|
||||||
case Z_AXIS:
|
case Z_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z));
|
||||||
if (index == 0) TMC_SET_STEALTH(Z);
|
TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2));
|
||||||
#endif
|
TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4));
|
||||||
if (index == 1) TMC_SET_STEALTH(Z2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
|
||||||
if (index == 2) TMC_SET_STEALTH(Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
if (index == 3) TMC_SET_STEALTH(Z4);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if I_HAS_STEALTHCHOP
|
||||||
|
case I_AXIS: TMC_SET_STEALTH(I); break;
|
||||||
|
#endif
|
||||||
|
#if J_HAS_STEALTHCHOP
|
||||||
|
case J_AXIS: TMC_SET_STEALTH(J); break;
|
||||||
|
#endif
|
||||||
|
#if K_HAS_STEALTHCHOP
|
||||||
|
case K_AXIS: TMC_SET_STEALTH(K); break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
case E_AXIS: {
|
case E_AXIS: {
|
||||||
if (target_extruder < 0) return;
|
if (target_extruder < 0) return;
|
||||||
switch (target_extruder) {
|
OPTCODE(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_STEALTH(E0))
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
OPTCODE(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_STEALTH(E1))
|
||||||
case 0: TMC_SET_STEALTH(E0); break;
|
OPTCODE(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_STEALTH(E2))
|
||||||
#endif
|
OPTCODE(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_STEALTH(E3))
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
OPTCODE(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_STEALTH(E4))
|
||||||
case 1: TMC_SET_STEALTH(E1); break;
|
OPTCODE(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_STEALTH(E5))
|
||||||
#endif
|
OPTCODE(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_STEALTH(E6))
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
OPTCODE(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_STEALTH(E7))
|
||||||
case 2: TMC_SET_STEALTH(E2); break;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
case 3: TMC_SET_STEALTH(E3); break;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
case 4: TMC_SET_STEALTH(E4); break;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
case 5: TMC_SET_STEALTH(E5); break;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
case 6: TMC_SET_STEALTH(E6); break;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
case 7: TMC_SET_STEALTH(E7); break;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
} break;
|
} break;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -126,55 +101,25 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
|
||||||
|
|
||||||
static void say_stealth_status() {
|
static void say_stealth_status() {
|
||||||
#define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q)
|
#define TMC_SAY_STEALTH_STATUS(Q) tmc_say_stealth_status(stepper##Q)
|
||||||
|
OPTCODE( X_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X))
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
OPTCODE(X2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(X2))
|
||||||
TMC_SAY_STEALTH_STATUS(X);
|
OPTCODE( Y_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y))
|
||||||
#endif
|
OPTCODE(Y2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Y2))
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
OPTCODE( Z_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z))
|
||||||
TMC_SAY_STEALTH_STATUS(X2);
|
OPTCODE(Z2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z2))
|
||||||
#endif
|
OPTCODE(Z3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z3))
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
OPTCODE(Z4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(Z4))
|
||||||
TMC_SAY_STEALTH_STATUS(Y);
|
OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I))
|
||||||
#endif
|
OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J))
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K))
|
||||||
TMC_SAY_STEALTH_STATUS(Y2);
|
OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0))
|
||||||
#endif
|
OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1))
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2))
|
||||||
TMC_SAY_STEALTH_STATUS(Z);
|
OPTCODE(E3_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E3))
|
||||||
#endif
|
OPTCODE(E4_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E4))
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
OPTCODE(E5_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E5))
|
||||||
TMC_SAY_STEALTH_STATUS(Z2);
|
OPTCODE(E6_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E6))
|
||||||
#endif
|
OPTCODE(E7_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E7))
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
|
||||||
TMC_SAY_STEALTH_STATUS(Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
TMC_SAY_STEALTH_STATUS(Z4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E0);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E1);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E5);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E6);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
TMC_SAY_STEALTH_STATUS(E7);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -48,7 +48,7 @@ void GcodeSuite::M906() {
|
||||||
|
|
||||||
bool report = true;
|
bool report = true;
|
||||||
|
|
||||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
|
||||||
const uint8_t index = parser.byteval('I');
|
const uint8_t index = parser.byteval('I');
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -64,7 +64,7 @@ void GcodeSuite::M906() {
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if LINEAR_AXES >= XY
|
#if HAS_Y_AXIS
|
||||||
case Y_AXIS:
|
case Y_AXIS:
|
||||||
#if AXIS_IS_TMC(Y)
|
#if AXIS_IS_TMC(Y)
|
||||||
if (index == 0) TMC_SET_CURRENT(Y);
|
if (index == 0) TMC_SET_CURRENT(Y);
|
||||||
|
@ -92,6 +92,16 @@ void GcodeSuite::M906() {
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
case I_AXIS: TMC_SET_CURRENT(I); break;
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
case J_AXIS: TMC_SET_CURRENT(J); break;
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
case K_AXIS: TMC_SET_CURRENT(K); break;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
case E_AXIS: {
|
case E_AXIS: {
|
||||||
const int8_t target_extruder = get_target_extruder_from_command();
|
const int8_t target_extruder = get_target_extruder_from_command();
|
||||||
|
@ -152,6 +162,15 @@ void GcodeSuite::M906() {
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
TMC_SAY_CURRENT(Z4);
|
TMC_SAY_CURRENT(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
TMC_SAY_CURRENT(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
TMC_SAY_CURRENT(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
TMC_SAY_CURRENT(K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
TMC_SAY_CURRENT(E0);
|
TMC_SAY_CURRENT(E0);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -38,18 +38,27 @@
|
||||||
#if M91x_USE(X) || M91x_USE(X2)
|
#if M91x_USE(X) || M91x_USE(X2)
|
||||||
#define M91x_SOME_X 1
|
#define M91x_SOME_X 1
|
||||||
#endif
|
#endif
|
||||||
#if M91x_USE(Y) || M91x_USE(Y2)
|
#if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2))
|
||||||
#define M91x_SOME_Y 1
|
#define M91x_SOME_Y 1
|
||||||
#endif
|
#endif
|
||||||
#if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4)
|
#if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
|
||||||
#define M91x_SOME_Z 1
|
#define M91x_SOME_Z 1
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && M91x_USE(I)
|
||||||
|
#define M91x_USE_I 1
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && M91x_USE(J)
|
||||||
|
#define M91x_USE_J 1
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && M91x_USE(K)
|
||||||
|
#define M91x_USE_K 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)
|
#if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)
|
||||||
#define M91x_SOME_E 1
|
#define M91x_SOME_E 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
|
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E
|
||||||
#error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
|
#error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -82,6 +91,9 @@
|
||||||
#if M91x_USE(Z4)
|
#if M91x_USE(Z4)
|
||||||
tmc_report_otpw(stepperZ4);
|
tmc_report_otpw(stepperZ4);
|
||||||
#endif
|
#endif
|
||||||
|
TERN_(M91x_USE_I, tmc_report_otpw(stepperI));
|
||||||
|
TERN_(M91x_USE_J, tmc_report_otpw(stepperJ));
|
||||||
|
TERN_(M91x_USE_K, tmc_report_otpw(stepperK));
|
||||||
#if M91x_USE_E(0)
|
#if M91x_USE_E(0)
|
||||||
tmc_report_otpw(stepperE0);
|
tmc_report_otpw(stepperE0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -124,9 +136,12 @@
|
||||||
const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)),
|
const bool hasX = TERN0(M91x_SOME_X, parser.seen(axis_codes.x)),
|
||||||
hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)),
|
hasY = TERN0(M91x_SOME_Y, parser.seen(axis_codes.y)),
|
||||||
hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)),
|
hasZ = TERN0(M91x_SOME_Z, parser.seen(axis_codes.z)),
|
||||||
|
hasI = TERN0(M91x_USE_I, parser.seen(axis_codes.i)),
|
||||||
|
hasJ = TERN0(M91x_USE_J, parser.seen(axis_codes.j)),
|
||||||
|
hasK = TERN0(M91x_USE_K, parser.seen(axis_codes.k)),
|
||||||
hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
|
hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
|
||||||
|
|
||||||
const bool hasNone = !hasE && !hasX && !hasY && !hasZ;
|
const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK;
|
||||||
|
|
||||||
#if M91x_SOME_X
|
#if M91x_SOME_X
|
||||||
const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));
|
const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));
|
||||||
|
@ -164,6 +179,19 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if M91x_USE_I
|
||||||
|
const int8_t ival = int8_t(parser.byteval(axis_codes.i, 0xFF));
|
||||||
|
if (hasNone || ival == 1 || (hasI && ival < 0)) tmc_clear_otpw(stepperI);
|
||||||
|
#endif
|
||||||
|
#if M91x_USE_J
|
||||||
|
const int8_t jval = int8_t(parser.byteval(axis_codes.j, 0xFF));
|
||||||
|
if (hasNone || jval == 1 || (hasJ && jval < 0)) tmc_clear_otpw(stepperJ);
|
||||||
|
#endif
|
||||||
|
#if M91x_USE_K
|
||||||
|
const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF));
|
||||||
|
if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if M91x_SOME_E
|
#if M91x_SOME_E
|
||||||
const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF));
|
const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF));
|
||||||
#if M91x_USE_E(0)
|
#if M91x_USE_E(0)
|
||||||
|
@ -206,126 +234,76 @@
|
||||||
#define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
|
#define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
|
||||||
|
|
||||||
bool report = true;
|
bool report = true;
|
||||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
|
||||||
const uint8_t index = parser.byteval('I');
|
const uint8_t index = parser.byteval('I');
|
||||||
#endif
|
#endif
|
||||||
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
|
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
|
||||||
report = false;
|
report = false;
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case X_AXIS:
|
case X_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X));
|
||||||
if (index < 2) TMC_SET_PWMTHRS(X,X);
|
TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2));
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
|
||||||
if (!(index & 1)) TMC_SET_PWMTHRS(X,X2);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
case Y_AXIS:
|
case Y_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y));
|
||||||
if (index < 2) TMC_SET_PWMTHRS(Y,Y);
|
TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2));
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
|
||||||
if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
#if I_HAS_STEALTHCHOP
|
||||||
|
case I_AXIS: TMC_SET_PWMTHRS(I,I); break;
|
||||||
|
#endif
|
||||||
|
#if J_HAS_STEALTHCHOP
|
||||||
|
case J_AXIS: TMC_SET_PWMTHRS(J,J); break;
|
||||||
|
#endif
|
||||||
|
#if K_HAS_STEALTHCHOP
|
||||||
|
case K_AXIS: TMC_SET_PWMTHRS(K,K); break;
|
||||||
|
#endif
|
||||||
|
|
||||||
case Z_AXIS:
|
case Z_AXIS:
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(Z_HAS_STEALTCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z));
|
||||||
if (index < 2) TMC_SET_PWMTHRS(Z,Z);
|
TERN_(Z2_HAS_STEALTCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2));
|
||||||
#endif
|
TERN_(Z3_HAS_STEALTCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(Z4_HAS_STEALTCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4));
|
||||||
if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
|
||||||
if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4);
|
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
case E_AXIS: {
|
case E_AXIS: {
|
||||||
#if E_STEPPERS
|
#if E_STEPPERS
|
||||||
const int8_t target_extruder = get_target_extruder_from_command();
|
const int8_t target_extruder = get_target_extruder_from_command();
|
||||||
if (target_extruder < 0) return;
|
if (target_extruder < 0) return;
|
||||||
switch (target_extruder) {
|
TERN_(E0_HAS_STEALTHCHOP, else if (target_extruder == 0) TMC_SET_PWMTHRS_E(0));
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
TERN_(E1_HAS_STEALTHCHOP, else if (target_extruder == 1) TMC_SET_PWMTHRS_E(1));
|
||||||
case 0: TMC_SET_PWMTHRS_E(0); break;
|
TERN_(E2_HAS_STEALTHCHOP, else if (target_extruder == 2) TMC_SET_PWMTHRS_E(2));
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, else if (target_extruder == 3) TMC_SET_PWMTHRS_E(3));
|
||||||
#if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
|
TERN_(E4_HAS_STEALTHCHOP, else if (target_extruder == 4) TMC_SET_PWMTHRS_E(4));
|
||||||
case 1: TMC_SET_PWMTHRS_E(1); break;
|
TERN_(E5_HAS_STEALTHCHOP, else if (target_extruder == 5) TMC_SET_PWMTHRS_E(5));
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, else if (target_extruder == 6) TMC_SET_PWMTHRS_E(6));
|
||||||
#if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
|
TERN_(E7_HAS_STEALTHCHOP, else if (target_extruder == 7) TMC_SET_PWMTHRS_E(7));
|
||||||
case 2: TMC_SET_PWMTHRS_E(2); break;
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
case 3: TMC_SET_PWMTHRS_E(3); break;
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
case 4: TMC_SET_PWMTHRS_E(4); break;
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
case 5: TMC_SET_PWMTHRS_E(5); break;
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
case 6: TMC_SET_PWMTHRS_E(6); break;
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
case 7: TMC_SET_PWMTHRS_E(7); break;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
#endif // E_STEPPERS
|
#endif // E_STEPPERS
|
||||||
} break;
|
} break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (report) {
|
if (report) {
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_( X_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X));
|
||||||
TMC_SAY_PWMTHRS(X,X);
|
TERN_(X2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(X,X2));
|
||||||
#endif
|
TERN_( Y_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y));
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(Y2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Y,Y2));
|
||||||
TMC_SAY_PWMTHRS(X,X2);
|
TERN_( Z_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z));
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z2));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(Z3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z3));
|
||||||
TMC_SAY_PWMTHRS(Y,Y);
|
TERN_(Z4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(Z,Z4));
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I));
|
||||||
TMC_SAY_PWMTHRS(Y,Y2);
|
TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J));
|
||||||
#endif
|
TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
|
||||||
TMC_SAY_PWMTHRS(Z,Z);
|
TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0));
|
||||||
#endif
|
TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E2_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(2));
|
||||||
TMC_SAY_PWMTHRS(Z,Z2);
|
TERN_(E3_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(3));
|
||||||
#endif
|
TERN_(E4_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(4));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
TERN_(E5_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(5));
|
||||||
TMC_SAY_PWMTHRS(Z,Z3);
|
TERN_(E6_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(6));
|
||||||
#endif
|
TERN_(E7_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(7));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
TMC_SAY_PWMTHRS(Z,Z4);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
TMC_SAY_PWMTHRS_E(0);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
TMC_SAY_PWMTHRS_E(1);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
TMC_SAY_PWMTHRS_E(2);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
TMC_SAY_PWMTHRS_E(3);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
TMC_SAY_PWMTHRS_E(4);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
TMC_SAY_PWMTHRS_E(5);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
TMC_SAY_PWMTHRS_E(6);
|
|
||||||
#endif
|
|
||||||
#if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
TMC_SAY_PWMTHRS_E(7);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // HYBRID_THRESHOLD
|
#endif // HYBRID_THRESHOLD
|
||||||
|
@ -378,6 +356,15 @@
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
|
||||||
|
case I_AXIS: stepperI.homing_threshold(value); break;
|
||||||
|
#endif
|
||||||
|
#if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
|
||||||
|
case J_AXIS: stepperJ.homing_threshold(value); break;
|
||||||
|
#endif
|
||||||
|
#if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
|
||||||
|
case K_AXIS: stepperK.homing_threshold(value); break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -412,6 +399,15 @@
|
||||||
tmc_print_sgt(stepperZ4);
|
tmc_print_sgt(stepperZ4);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
|
||||||
|
tmc_print_sgt(stepperI);
|
||||||
|
#endif
|
||||||
|
#if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
|
||||||
|
tmc_print_sgt(stepperJ);
|
||||||
|
#endif
|
||||||
|
#if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
|
||||||
|
tmc_print_sgt(stepperK);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif // USE_SENSORLESS
|
#endif // USE_SENSORLESS
|
||||||
|
|
|
@ -78,7 +78,10 @@ uint8_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG(
|
||||||
| (ar_init.e << REL_E),
|
| (ar_init.e << REL_E),
|
||||||
| (ar_init.x << REL_X),
|
| (ar_init.x << REL_X),
|
||||||
| (ar_init.y << REL_Y),
|
| (ar_init.y << REL_Y),
|
||||||
| (ar_init.z << REL_Z)
|
| (ar_init.z << REL_Z),
|
||||||
|
| (ar_init.i << REL_I),
|
||||||
|
| (ar_init.j << REL_J),
|
||||||
|
| (ar_init.k << REL_K)
|
||||||
);
|
);
|
||||||
|
|
||||||
#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
|
#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
|
||||||
|
|
|
@ -315,7 +315,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
enum AxisRelative : uint8_t {
|
enum AxisRelative : uint8_t {
|
||||||
LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z)
|
LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K)
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
, E_MODE_ABS, E_MODE_REL
|
, E_MODE_ABS, E_MODE_REL
|
||||||
#endif
|
#endif
|
||||||
|
@ -338,7 +338,11 @@ public:
|
||||||
return TEST(axis_relative, a);
|
return TEST(axis_relative, a);
|
||||||
}
|
}
|
||||||
static inline void set_relative_mode(const bool rel) {
|
static inline void set_relative_mode(const bool rel) {
|
||||||
axis_relative = rel ? (0 LOGICAL_AXIS_GANG(| _BV(REL_E), | _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z))) : 0;
|
axis_relative = rel ? (0 LOGICAL_AXIS_GANG(
|
||||||
|
| _BV(REL_E),
|
||||||
|
| _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z),
|
||||||
|
| _BV(REL_I), | _BV(REL_J), | _BV(REL_K)
|
||||||
|
)) : 0;
|
||||||
}
|
}
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
static inline void set_e_relative() {
|
static inline void set_e_relative() {
|
||||||
|
|
|
@ -31,7 +31,16 @@
|
||||||
#include "../../MarlinCore.h"
|
#include "../../MarlinCore.h"
|
||||||
|
|
||||||
void M206_report() {
|
void M206_report() {
|
||||||
SERIAL_ECHOLNPAIR_P(PSTR("M206 X"), home_offset.x, SP_Y_STR, home_offset.y, SP_Z_STR, home_offset.z);
|
SERIAL_ECHOLNPAIR_P(
|
||||||
|
LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
|
PSTR("M206 X"), home_offset.x,
|
||||||
|
SP_Y_STR, home_offset.y,
|
||||||
|
SP_Z_STR, home_offset.z,
|
||||||
|
SP_I_STR, home_offset.i,
|
||||||
|
SP_J_STR, home_offset.j,
|
||||||
|
SP_K_STR, home_offset.k,
|
||||||
|
)
|
||||||
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -51,7 +60,7 @@ void GcodeSuite::M206() {
|
||||||
if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
|
if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!parser.seen("XYZ"))
|
if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", "I", "J", "K")))
|
||||||
M206_report();
|
M206_report();
|
||||||
else
|
else
|
||||||
report_current_position();
|
report_current_position();
|
||||||
|
|
|
@ -125,6 +125,15 @@
|
||||||
#if AXIS_IS_L64XX(Z4)
|
#if AXIS_IS_L64XX(Z4)
|
||||||
REPORT_ABSOLUTE_POS(Z4);
|
REPORT_ABSOLUTE_POS(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
REPORT_ABSOLUTE_POS(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
REPORT_ABSOLUTE_POS(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
REPORT_ABSOLUTE_POS(K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
REPORT_ABSOLUTE_POS(E0);
|
REPORT_ABSOLUTE_POS(E0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -170,7 +179,13 @@
|
||||||
|
|
||||||
SERIAL_ECHOPGM("FromStp:");
|
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);
|
xyze_pos_t from_steppers = LOGICAL_AXIS_ARRAY(
|
||||||
|
planner.get_axis_position_mm(E_AXIS),
|
||||||
|
cartes.x, cartes.y, cartes.z,
|
||||||
|
planner.get_axis_position_mm(I_AXIS),
|
||||||
|
planner.get_axis_position_mm(J_AXIS),
|
||||||
|
planner.get_axis_position_mm(K_AXIS)
|
||||||
|
);
|
||||||
report_all_axis_pos(from_steppers);
|
report_all_axis_pos(from_steppers);
|
||||||
|
|
||||||
const xyze_float_t diff = from_steppers - leveled;
|
const xyze_float_t diff = from_steppers - leveled;
|
||||||
|
|
|
@ -52,7 +52,10 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
(parser.seen_test('X') ? _BV(X_AXIS) : 0),
|
(parser.seen_test('X') ? _BV(X_AXIS) : 0),
|
||||||
| (parser.seen_test('Y') ? _BV(Y_AXIS) : 0),
|
| (parser.seen_test('Y') ? _BV(Y_AXIS) : 0),
|
||||||
| (parser.seen_test('Z') ? _BV(Z_AXIS) : 0))
|
| (parser.seen_test('Z') ? _BV(Z_AXIS) : 0),
|
||||||
|
| (parser.seen_test(AXIS4_NAME) ? _BV(I_AXIS) : 0),
|
||||||
|
| (parser.seen_test(AXIS5_NAME) ? _BV(J_AXIS) : 0),
|
||||||
|
| (parser.seen_test(AXIS6_NAME) ? _BV(K_AXIS) : 0))
|
||||||
)
|
)
|
||||||
#endif
|
#endif
|
||||||
) {
|
) {
|
||||||
|
@ -85,7 +88,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
|
||||||
|
|
||||||
if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
|
if (MIN_AUTORETRACT <= MAX_AUTORETRACT) {
|
||||||
// When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves
|
// When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves
|
||||||
if (fwretract.autoretract_enabled && parser.seen_test('E') && !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z"))) {
|
if (fwretract.autoretract_enabled && parser.seen_test('E')
|
||||||
|
&& !parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))
|
||||||
|
) {
|
||||||
const float echange = destination.e - current_position.e;
|
const float echange = destination.e - current_position.e;
|
||||||
// Is this a retract or recover move?
|
// Is this a retract or recover move?
|
||||||
if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) {
|
if (WITHIN(ABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && fwretract.retracted[active_extruder] == (echange > 0.0)) {
|
||||||
|
|
|
@ -63,7 +63,7 @@ void plan_arc(
|
||||||
case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break;
|
case GcodeSuite::PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS;
|
constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS OPTARG(HAS_Z_AXIS, l_axis = Z_AXIS);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Radius vector from center to current location
|
// Radius vector from center to current location
|
||||||
|
@ -73,8 +73,8 @@ void plan_arc(
|
||||||
center_P = current_position[p_axis] - rvec.a,
|
center_P = current_position[p_axis] - rvec.a,
|
||||||
center_Q = current_position[q_axis] - rvec.b,
|
center_Q = current_position[q_axis] - rvec.b,
|
||||||
rt_X = cart[p_axis] - center_P,
|
rt_X = cart[p_axis] - center_P,
|
||||||
rt_Y = cart[q_axis] - center_Q,
|
rt_Y = cart[q_axis] - center_Q
|
||||||
start_L = current_position[l_axis];
|
OPTARG(HAS_Z_AXIS, start_L = current_position[l_axis]);
|
||||||
|
|
||||||
#ifdef MIN_ARC_SEGMENTS
|
#ifdef MIN_ARC_SEGMENTS
|
||||||
uint16_t min_segments = MIN_ARC_SEGMENTS;
|
uint16_t min_segments = MIN_ARC_SEGMENTS;
|
||||||
|
@ -109,8 +109,9 @@ void plan_arc(
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
float linear_travel = cart[l_axis] - start_L;
|
float linear_travel = cart[l_axis] - start_L;
|
||||||
|
#endif
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
float extruder_travel = cart.e - current_position.e;
|
float extruder_travel = cart.e - current_position.e;
|
||||||
#endif
|
#endif
|
||||||
|
@ -118,9 +119,11 @@ void plan_arc(
|
||||||
// If circling around...
|
// If circling around...
|
||||||
if (ENABLED(ARC_P_CIRCLES) && circles) {
|
if (ENABLED(ARC_P_CIRCLES) && circles) {
|
||||||
const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder
|
const float total_angular = angular_travel + circles * RADIANS(360), // Total rotation with all circles and remainder
|
||||||
part_per_circle = RADIANS(360) / total_angular, // Each circle's part of the total
|
part_per_circle = RADIANS(360) / total_angular; // Each circle's part of the total
|
||||||
l_per_circle = linear_travel * part_per_circle; // L movement per circle
|
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
const float l_per_circle = linear_travel * part_per_circle; // L movement per circle
|
||||||
|
#endif
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle
|
const float e_per_circle = extruder_travel * part_per_circle; // E movement per circle
|
||||||
#endif
|
#endif
|
||||||
|
@ -128,17 +131,15 @@ void plan_arc(
|
||||||
xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position
|
xyze_pos_t temp_position = current_position; // for plan_arc to compare to current_position
|
||||||
for (uint16_t n = circles; n--;) {
|
for (uint16_t n = circles; n--;) {
|
||||||
TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis
|
TERN_(HAS_EXTRUDERS, temp_position.e += e_per_circle); // Destination E axis
|
||||||
temp_position[l_axis] += l_per_circle; // Destination L axis
|
TERN_(HAS_Z_AXIS, temp_position[l_axis] += l_per_circle); // Destination L axis
|
||||||
plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle
|
plan_arc(temp_position, offset, clockwise, 0); // Plan a single whole circle
|
||||||
}
|
}
|
||||||
linear_travel = cart[l_axis] - current_position[l_axis];
|
TERN_(HAS_Z_AXIS, linear_travel = cart[l_axis] - current_position[l_axis]);
|
||||||
#if HAS_EXTRUDERS
|
TERN_(HAS_EXTRUDERS, extruder_travel = cart.e - current_position.e);
|
||||||
extruder_travel = cart.e - current_position.e;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const float flat_mm = radius * angular_travel,
|
const float flat_mm = radius * angular_travel,
|
||||||
mm_of_travel = linear_travel ? HYPOT(flat_mm, linear_travel) : ABS(flat_mm);
|
mm_of_travel = TERN_(HAS_Z_AXIS, linear_travel ? HYPOT(flat_mm, linear_travel) :) ABS(flat_mm);
|
||||||
if (mm_of_travel < 0.001f) return;
|
if (mm_of_travel < 0.001f) return;
|
||||||
|
|
||||||
const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s);
|
const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s);
|
||||||
|
@ -187,17 +188,19 @@ void plan_arc(
|
||||||
// Vector rotation matrix values
|
// Vector rotation matrix values
|
||||||
xyze_pos_t raw;
|
xyze_pos_t raw;
|
||||||
const float theta_per_segment = angular_travel / segments,
|
const float theta_per_segment = angular_travel / segments,
|
||||||
linear_per_segment = linear_travel / segments,
|
|
||||||
sq_theta_per_segment = sq(theta_per_segment),
|
sq_theta_per_segment = sq(theta_per_segment),
|
||||||
sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6,
|
sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6,
|
||||||
cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
|
cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS && DISABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
const float linear_per_segment = linear_travel / segments;
|
||||||
|
#endif
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
const float extruder_per_segment = extruder_travel / segments;
|
const float extruder_per_segment = extruder_travel / segments;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Initialize the linear axis
|
// Initialize the linear axis
|
||||||
raw[l_axis] = current_position[l_axis];
|
TERN_(HAS_Z_AXIS, raw[l_axis] = current_position[l_axis]);
|
||||||
|
|
||||||
// Initialize the extruder axis
|
// Initialize the extruder axis
|
||||||
TERN_(HAS_EXTRUDERS, raw.e = current_position.e);
|
TERN_(HAS_EXTRUDERS, raw.e = current_position.e);
|
||||||
|
@ -246,11 +249,8 @@ void plan_arc(
|
||||||
// Update raw location
|
// Update raw location
|
||||||
raw[p_axis] = center_P + rvec.a;
|
raw[p_axis] = center_P + rvec.a;
|
||||||
raw[q_axis] = center_Q + rvec.b;
|
raw[q_axis] = center_Q + rvec.b;
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if HAS_Z_AXIS
|
||||||
raw[l_axis] = start_L;
|
raw[l_axis] = TERN(AUTO_BED_LEVELING_UBL, start_L, raw[l_axis] + linear_per_segment);
|
||||||
UNUSED(linear_per_segment);
|
|
||||||
#else
|
|
||||||
raw[l_axis] += linear_per_segment;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment);
|
TERN_(HAS_EXTRUDERS, raw.e += extruder_per_segment);
|
||||||
|
@ -268,7 +268,7 @@ void plan_arc(
|
||||||
|
|
||||||
// Ensure last segment arrives at target location.
|
// Ensure last segment arrives at target location.
|
||||||
raw = cart;
|
raw = cart;
|
||||||
TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
|
TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L));
|
||||||
|
|
||||||
apply_motion_limits(raw);
|
apply_motion_limits(raw);
|
||||||
|
|
||||||
|
@ -280,7 +280,7 @@ void plan_arc(
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
||||||
);
|
);
|
||||||
|
|
||||||
TERN_(AUTO_BED_LEVELING_UBL, raw[l_axis] = start_L);
|
TERN_(AUTO_BED_LEVELING_UBL, TERN_(HAS_Z_AXIS, raw[l_axis] = start_L));
|
||||||
current_position = raw;
|
current_position = raw;
|
||||||
|
|
||||||
} // plan_arc
|
} // plan_arc
|
||||||
|
|
|
@ -87,7 +87,7 @@ void GcodeSuite::M290() {
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z")) || parser.seen('R')) {
|
if (!parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)) || parser.seen('R')) {
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
|
|
||||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||||
|
|
|
@ -248,7 +248,7 @@ void GCodeParser::parse(char *p) {
|
||||||
case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return;
|
case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':)
|
LOGICAL_AXIS_GANG(case 'E':, case 'X':, case 'Y':, case 'Z':, case AXIS4_NAME:, case AXIS5_NAME:, case AXIS6_NAME:)
|
||||||
case 'F':
|
case 'F':
|
||||||
if (motion_mode_codenum < 0) return;
|
if (motion_mode_codenum < 0) return;
|
||||||
command_letter = 'G';
|
command_letter = 'G';
|
||||||
|
|
|
@ -226,7 +226,7 @@ public:
|
||||||
|
|
||||||
// Seen any axis parameter
|
// Seen any axis parameter
|
||||||
static inline bool seen_axis() {
|
static inline bool seen_axis() {
|
||||||
return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z"));
|
return seen(LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR));
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(GCODE_QUOTED_STRINGS)
|
#if ENABLED(GCODE_QUOTED_STRINGS)
|
||||||
|
|
|
@ -83,6 +83,8 @@ void GcodeSuite::M106() {
|
||||||
if (!got_preset && parser.seenval('S'))
|
if (!got_preset && parser.seenval('S'))
|
||||||
speed = parser.value_ushort();
|
speed = parser.value_ushort();
|
||||||
|
|
||||||
|
TERN_(FOAMCUTTER_XYUV, speed *= 2.55); // Get command in % of max heat
|
||||||
|
|
||||||
// Set speed, with constraint
|
// Set speed, with constraint
|
||||||
thermalManager.set_fan_speed(pfan, speed);
|
thermalManager.set_fan_speed(pfan, speed);
|
||||||
|
|
||||||
|
|
|
@ -612,6 +612,12 @@
|
||||||
#ifndef LINEAR_AXES
|
#ifndef LINEAR_AXES
|
||||||
#define LINEAR_AXES XYZ
|
#define LINEAR_AXES XYZ
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= XY
|
||||||
|
#define HAS_Y_AXIS 1
|
||||||
|
#if LINEAR_AXES >= XYZ
|
||||||
|
#define HAS_Z_AXIS 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Number of Logical Axes (e.g., XYZE)
|
* Number of Logical Axes (e.g., XYZE)
|
||||||
|
@ -624,10 +630,6 @@
|
||||||
#define LOGICAL_AXES LINEAR_AXES
|
#define LOGICAL_AXES LINEAR_AXES
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if LINEAR_AXES >= XYZ
|
|
||||||
#define HAS_Z_AXIS 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* DISTINCT_E_FACTORS is set to give extruders (some) individual settings.
|
* DISTINCT_E_FACTORS is set to give extruders (some) individual settings.
|
||||||
*
|
*
|
||||||
|
@ -852,6 +854,21 @@
|
||||||
#elif Z_HOME_DIR < 0
|
#elif Z_HOME_DIR < 0
|
||||||
#define Z_HOME_TO_MIN 1
|
#define Z_HOME_TO_MIN 1
|
||||||
#endif
|
#endif
|
||||||
|
#if I_HOME_DIR > 0
|
||||||
|
#define I_HOME_TO_MAX 1
|
||||||
|
#elif I_HOME_DIR < 0
|
||||||
|
#define I_HOME_TO_MIN 1
|
||||||
|
#endif
|
||||||
|
#if J_HOME_DIR > 0
|
||||||
|
#define J_HOME_TO_MAX 1
|
||||||
|
#elif J_HOME_DIR < 0
|
||||||
|
#define J_HOME_TO_MIN 1
|
||||||
|
#endif
|
||||||
|
#if K_HOME_DIR > 0
|
||||||
|
#define K_HOME_TO_MAX 1
|
||||||
|
#elif K_HOME_DIR < 0
|
||||||
|
#define K_HOME_TO_MIN 1
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Conditionals based on the type of Bed Probe
|
* Conditionals based on the type of Bed Probe
|
||||||
|
@ -1110,13 +1127,22 @@
|
||||||
#ifndef INVERT_X_DIR
|
#ifndef INVERT_X_DIR
|
||||||
#define INVERT_X_DIR false
|
#define INVERT_X_DIR false
|
||||||
#endif
|
#endif
|
||||||
#ifndef INVERT_Y_DIR
|
#if HAS_Y_AXIS && !defined(INVERT_Y_DIR)
|
||||||
#define INVERT_Y_DIR false
|
#define INVERT_Y_DIR false
|
||||||
#endif
|
#endif
|
||||||
#ifndef INVERT_Z_DIR
|
#if HAS_Z_AXIS && !defined(INVERT_Z_DIR)
|
||||||
#define INVERT_Z_DIR false
|
#define INVERT_Z_DIR false
|
||||||
#endif
|
#endif
|
||||||
#ifndef INVERT_E_DIR
|
#if LINEAR_AXES >= 4 && !defined(INVERT_I_DIR)
|
||||||
|
#define INVERT_I_DIR false
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && !defined(INVERT_J_DIR)
|
||||||
|
#define INVERT_J_DIR false
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && !defined(INVERT_K_DIR)
|
||||||
|
#define INVERT_K_DIR false
|
||||||
|
#endif
|
||||||
|
#if HAS_EXTRUDERS && !defined(INVERT_E_DIR)
|
||||||
#define INVERT_E_DIR false
|
#define INVERT_E_DIR false
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -26,6 +26,10 @@
|
||||||
* Defines that depend on advanced configuration.
|
* Defines that depend on advanced configuration.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#ifndef AXIS_RELATIVE_MODES
|
||||||
|
#define AXIS_RELATIVE_MODES {}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef SWITCHING_NOZZLE_E1_SERVO_NR
|
#ifdef SWITCHING_NOZZLE_E1_SERVO_NR
|
||||||
#define SWITCHING_NOZZLE_TWO_SERVOS 1
|
#define SWITCHING_NOZZLE_TWO_SERVOS 1
|
||||||
#endif
|
#endif
|
||||||
|
@ -488,12 +492,26 @@
|
||||||
// Remove unused STEALTHCHOP flags
|
// Remove unused STEALTHCHOP flags
|
||||||
#if LINEAR_AXES < 6
|
#if LINEAR_AXES < 6
|
||||||
#undef STEALTHCHOP_K
|
#undef STEALTHCHOP_K
|
||||||
|
#undef CALIBRATION_MEASURE_KMIN
|
||||||
|
#undef CALIBRATION_MEASURE_KMAX
|
||||||
#if LINEAR_AXES < 5
|
#if LINEAR_AXES < 5
|
||||||
#undef STEALTHCHOP_J
|
#undef STEALTHCHOP_J
|
||||||
|
#undef CALIBRATION_MEASURE_JMIN
|
||||||
|
#undef CALIBRATION_MEASURE_JMAX
|
||||||
#if LINEAR_AXES < 4
|
#if LINEAR_AXES < 4
|
||||||
#undef STEALTHCHOP_I
|
#undef STEALTHCHOP_I
|
||||||
|
#undef CALIBRATION_MEASURE_IMIN
|
||||||
|
#undef CALIBRATION_MEASURE_IMAX
|
||||||
#if LINEAR_AXES < 3
|
#if LINEAR_AXES < 3
|
||||||
|
#undef Z_IDLE_HEIGHT
|
||||||
#undef STEALTHCHOP_Z
|
#undef STEALTHCHOP_Z
|
||||||
|
#undef Z_PROBE_SLED
|
||||||
|
#undef Z_SAFE_HOMING
|
||||||
|
#undef HOME_Z_FIRST
|
||||||
|
#undef HOMING_Z_WITH_PROBE
|
||||||
|
#undef ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
#undef NUM_Z_STEPPER_DRIVERS
|
||||||
|
#undef CNC_WORKSPACE_PLANES
|
||||||
#if LINEAR_AXES < 2
|
#if LINEAR_AXES < 2
|
||||||
#undef STEALTHCHOP_Y
|
#undef STEALTHCHOP_Y
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -78,17 +78,49 @@
|
||||||
/**
|
/**
|
||||||
* Axis lengths and center
|
* Axis lengths and center
|
||||||
*/
|
*/
|
||||||
|
#ifndef AXIS4_NAME
|
||||||
|
#define AXIS4_NAME 'A'
|
||||||
|
#endif
|
||||||
|
#ifndef AXIS5_NAME
|
||||||
|
#define AXIS5_NAME 'B'
|
||||||
|
#endif
|
||||||
|
#ifndef AXIS6_NAME
|
||||||
|
#define AXIS6_NAME 'C'
|
||||||
|
#endif
|
||||||
|
|
||||||
#define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
|
#define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
|
||||||
#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
|
#if HAS_Y_AXIS
|
||||||
#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
|
#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define I_MAX_LENGTH (I_MAX_POS - (I_MIN_POS))
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define J_MAX_LENGTH (J_MAX_POS - (J_MIN_POS))
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define K_MAX_LENGTH (K_MAX_POS - (K_MIN_POS))
|
||||||
|
#endif
|
||||||
|
|
||||||
// Defined only if the sanity-check is bypassed
|
// Defined only if the sanity-check is bypassed
|
||||||
#ifndef X_BED_SIZE
|
#ifndef X_BED_SIZE
|
||||||
#define X_BED_SIZE X_MAX_LENGTH
|
#define X_BED_SIZE X_MAX_LENGTH
|
||||||
#endif
|
#endif
|
||||||
#ifndef Y_BED_SIZE
|
#if HAS_Y_AXIS && !defined(Y_BED_SIZE)
|
||||||
#define Y_BED_SIZE Y_MAX_LENGTH
|
#define Y_BED_SIZE Y_MAX_LENGTH
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && !defined(I_BED_SIZE)
|
||||||
|
#define I_BED_SIZE I_MAX_LENGTH
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && !defined(J_BED_SIZE)
|
||||||
|
#define J_BED_SIZE J_MAX_LENGTH
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && !defined(K_BED_SIZE)
|
||||||
|
#define K_BED_SIZE K_MAX_LENGTH
|
||||||
|
#endif
|
||||||
|
|
||||||
// Require 0,0 bed center for Delta and SCARA
|
// Require 0,0 bed center for Delta and SCARA
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
|
@ -97,16 +129,53 @@
|
||||||
|
|
||||||
// Define center values for future use
|
// Define center values for future use
|
||||||
#define _X_HALF_BED ((X_BED_SIZE) / 2)
|
#define _X_HALF_BED ((X_BED_SIZE) / 2)
|
||||||
#define _Y_HALF_BED ((Y_BED_SIZE) / 2)
|
#if HAS_Y_AXIS
|
||||||
|
#define _Y_HALF_BED ((Y_BED_SIZE) / 2)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define _I_HALF_IMAX ((I_BED_SIZE) / 2)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define _J_HALF_JMAX ((J_BED_SIZE) / 2)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define _K_HALF_KMAX ((K_BED_SIZE) / 2)
|
||||||
|
#endif
|
||||||
|
|
||||||
#define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED)
|
#define X_CENTER TERN(BED_CENTER_AT_0_0, 0, _X_HALF_BED)
|
||||||
#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED)
|
#if HAS_Y_AXIS
|
||||||
#define XY_CENTER { X_CENTER, Y_CENTER }
|
#define Y_CENTER TERN(BED_CENTER_AT_0_0, 0, _Y_HALF_BED)
|
||||||
|
#define XY_CENTER { X_CENTER, Y_CENTER }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define I_CENTER TERN(BED_CENTER_AT_0_0, 0, _I_HALF_BED)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define J_CENTER TERN(BED_CENTER_AT_0_0, 0, _J_HALF_BED)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define K_CENTER TERN(BED_CENTER_AT_0_0, 0, _K_HALF_BED)
|
||||||
|
#endif
|
||||||
|
|
||||||
// Get the linear boundaries of the bed
|
// Get the linear boundaries of the bed
|
||||||
#define X_MIN_BED (X_CENTER - _X_HALF_BED)
|
#define X_MIN_BED (X_CENTER - _X_HALF_BED)
|
||||||
#define X_MAX_BED (X_MIN_BED + X_BED_SIZE)
|
#define X_MAX_BED (X_MIN_BED + X_BED_SIZE)
|
||||||
#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED)
|
#if HAS_Y_AXIS
|
||||||
#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE)
|
#define Y_MIN_BED (Y_CENTER - _Y_HALF_BED)
|
||||||
|
#define Y_MAX_BED (Y_MIN_BED + Y_BED_SIZE)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define I_MINIM (I_CENTER - _I_HALF_BED_SIZE)
|
||||||
|
#define I_MAXIM (I_MINIM + I_BED_SIZE)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define J_MINIM (J_CENTER - _J_HALF_BED_SIZE)
|
||||||
|
#define J_MAXIM (J_MINIM + J_BED_SIZE)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define K_MINIM (K_CENTER - _K_HALF_BED_SIZE)
|
||||||
|
#define K_MAXIM (K_MINIM + K_BED_SIZE)
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Dual X Carriage
|
* Dual X Carriage
|
||||||
|
@ -163,15 +232,17 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MANUAL_Y_HOME_POS
|
#if HAS_Y_AXIS
|
||||||
|
#ifdef MANUAL_Y_HOME_POS
|
||||||
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
#define Y_HOME_POS MANUAL_Y_HOME_POS
|
||||||
#else
|
#else
|
||||||
#define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS)
|
#define Y_END_POS TERN(Y_HOME_TO_MIN, Y_MIN_POS, Y_MAX_POS)
|
||||||
#if ENABLED(BED_CENTER_AT_0_0)
|
#if ENABLED(BED_CENTER_AT_0_0)
|
||||||
#define Y_HOME_POS TERN(DELTA, 0, Y_END_POS)
|
#define Y_HOME_POS TERN(DELTA, 0, Y_END_POS)
|
||||||
#else
|
#else
|
||||||
#define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS)
|
#define Y_HOME_POS TERN(DELTA, Y_MIN_POS + (Y_BED_SIZE) * 0.5, Y_END_POS)
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MANUAL_Z_HOME_POS
|
#ifdef MANUAL_Z_HOME_POS
|
||||||
|
@ -180,6 +251,28 @@
|
||||||
#define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS)
|
#define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#ifdef MANUAL_I_HOME_POS
|
||||||
|
#define I_HOME_POS MANUAL_I_HOME_POS
|
||||||
|
#else
|
||||||
|
#define I_HOME_POS TERN(I_HOME_TO_MIN, I_MIN_POS, I_MAX_POS)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#ifdef MANUAL_J_HOME_POS
|
||||||
|
#define J_HOME_POS MANUAL_J_HOME_POS
|
||||||
|
#else
|
||||||
|
#define J_HOME_POS TERN(J_HOME_TO_MIN, J_MIN_POS, J_MAX_POS)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#ifdef MANUAL_K_HOME_POS
|
||||||
|
#define K_HOME_POS MANUAL_K_HOME_POS
|
||||||
|
#else
|
||||||
|
#define K_HOME_POS TERN(K_HOME_TO_MIN, K_MIN_POS, K_MAX_POS)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* If DELTA_HEIGHT isn't defined use the old setting
|
* If DELTA_HEIGHT isn't defined use the old setting
|
||||||
*/
|
*/
|
||||||
|
@ -374,15 +467,24 @@
|
||||||
#ifndef DISABLE_INACTIVE_X
|
#ifndef DISABLE_INACTIVE_X
|
||||||
#define DISABLE_INACTIVE_X DISABLE_X
|
#define DISABLE_INACTIVE_X DISABLE_X
|
||||||
#endif
|
#endif
|
||||||
#ifndef DISABLE_INACTIVE_Y
|
#if HAS_Y_AXIS && !defined(DISABLE_INACTIVE_Y)
|
||||||
#define DISABLE_INACTIVE_Y DISABLE_Y
|
#define DISABLE_INACTIVE_Y DISABLE_Y
|
||||||
#endif
|
#endif
|
||||||
#ifndef DISABLE_INACTIVE_Z
|
#if HAS_Z_AXIS && !defined(DISABLE_INACTIVE_Z)
|
||||||
#define DISABLE_INACTIVE_Z DISABLE_Z
|
#define DISABLE_INACTIVE_Z DISABLE_Z
|
||||||
#endif
|
#endif
|
||||||
#ifndef DISABLE_INACTIVE_E
|
#ifndef DISABLE_INACTIVE_E
|
||||||
#define DISABLE_INACTIVE_E DISABLE_E
|
#define DISABLE_INACTIVE_E DISABLE_E
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && !defined(DISABLE_INACTIVE_I)
|
||||||
|
#define DISABLE_INACTIVE_I DISABLE_I
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && !defined(DISABLE_INACTIVE_J)
|
||||||
|
#define DISABLE_INACTIVE_J DISABLE_J
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && !defined(DISABLE_INACTIVE_K)
|
||||||
|
#define DISABLE_INACTIVE_K DISABLE_K
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Power Supply
|
* Power Supply
|
||||||
|
@ -1418,6 +1520,15 @@
|
||||||
#if ENABLED(USE_ZMAX_PLUG)
|
#if ENABLED(USE_ZMAX_PLUG)
|
||||||
#define ENDSTOPPULLUP_ZMAX
|
#define ENDSTOPPULLUP_ZMAX
|
||||||
#endif
|
#endif
|
||||||
|
#if ENABLED(USE_IMAX_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_IMAX
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_JMAX_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_JMAX
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_KMAX_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_KMAX
|
||||||
|
#endif
|
||||||
#if ENABLED(USE_XMIN_PLUG)
|
#if ENABLED(USE_XMIN_PLUG)
|
||||||
#define ENDSTOPPULLUP_XMIN
|
#define ENDSTOPPULLUP_XMIN
|
||||||
#endif
|
#endif
|
||||||
|
@ -1427,6 +1538,15 @@
|
||||||
#if ENABLED(USE_ZMIN_PLUG)
|
#if ENABLED(USE_ZMIN_PLUG)
|
||||||
#define ENDSTOPPULLUP_ZMIN
|
#define ENDSTOPPULLUP_ZMIN
|
||||||
#endif
|
#endif
|
||||||
|
#if ENABLED(USE_IMIN_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_IMIN
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_JMIN_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_JMIN
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_KMIN_PLUG)
|
||||||
|
#define ENDSTOPPULLUP_KMIN
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1484,82 +1604,137 @@
|
||||||
#define HAS_X2_MS_PINS 1
|
#define HAS_X2_MS_PINS 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
|
#if HAS_Y_AXIS
|
||||||
|
#if PIN_EXISTS(Y_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y))
|
||||||
#define HAS_Y_ENABLE 1
|
#define HAS_Y_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_DIR)
|
#if PIN_EXISTS(Y_DIR)
|
||||||
#define HAS_Y_DIR 1
|
#define HAS_Y_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_STEP)
|
#if PIN_EXISTS(Y_STEP)
|
||||||
#define HAS_Y_STEP 1
|
#define HAS_Y_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MS1)
|
#if PIN_EXISTS(Y_MS1)
|
||||||
#define HAS_Y_MS_PINS 1
|
#define HAS_Y_MS_PINS 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
|
#if PIN_EXISTS(Y2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Y2))
|
||||||
#define HAS_Y2_ENABLE 1
|
#define HAS_Y2_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y2_DIR)
|
#if PIN_EXISTS(Y2_DIR)
|
||||||
#define HAS_Y2_DIR 1
|
#define HAS_Y2_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y2_STEP)
|
#if PIN_EXISTS(Y2_STEP)
|
||||||
#define HAS_Y2_STEP 1
|
#define HAS_Y2_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y2_MS1)
|
#if PIN_EXISTS(Y2_MS1)
|
||||||
#define HAS_Y2_MS_PINS 1
|
#define HAS_Y2_MS_PINS 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
|
#if HAS_Z_AXIS
|
||||||
|
#if PIN_EXISTS(Z_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z))
|
||||||
#define HAS_Z_ENABLE 1
|
#define HAS_Z_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_DIR)
|
#if PIN_EXISTS(Z_DIR)
|
||||||
#define HAS_Z_DIR 1
|
#define HAS_Z_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_STEP)
|
#if PIN_EXISTS(Z_STEP)
|
||||||
#define HAS_Z_STEP 1
|
#define HAS_Z_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MS1)
|
#if PIN_EXISTS(Z_MS1)
|
||||||
#define HAS_Z_MS_PINS 1
|
#define HAS_Z_MS_PINS 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
|
#if NUM_Z_STEPPER_DRIVERS >= 2
|
||||||
|
#if PIN_EXISTS(Z2_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z2))
|
||||||
#define HAS_Z2_ENABLE 1
|
#define HAS_Z2_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z2_DIR)
|
#if PIN_EXISTS(Z2_DIR)
|
||||||
#define HAS_Z2_DIR 1
|
#define HAS_Z2_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z2_STEP)
|
#if PIN_EXISTS(Z2_STEP)
|
||||||
#define HAS_Z2_STEP 1
|
#define HAS_Z2_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z2_MS1)
|
#if PIN_EXISTS(Z2_MS1)
|
||||||
#define HAS_Z2_MS_PINS 1
|
#define HAS_Z2_MS_PINS 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
|
#if NUM_Z_STEPPER_DRIVERS >= 3
|
||||||
|
#if PIN_EXISTS(Z3_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z3))
|
||||||
#define HAS_Z3_ENABLE 1
|
#define HAS_Z3_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z3_DIR)
|
#if PIN_EXISTS(Z3_DIR)
|
||||||
#define HAS_Z3_DIR 1
|
#define HAS_Z3_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z3_STEP)
|
#if PIN_EXISTS(Z3_STEP)
|
||||||
#define HAS_Z3_STEP 1
|
#define HAS_Z3_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z3_MS1)
|
#if PIN_EXISTS(Z3_MS1)
|
||||||
#define HAS_Z3_MS_PINS 1
|
#define HAS_Z3_MS_PINS 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
|
#if NUM_Z_STEPPER_DRIVERS >= 4
|
||||||
|
#if PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4))
|
||||||
#define HAS_Z4_ENABLE 1
|
#define HAS_Z4_ENABLE 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z4_DIR)
|
#if PIN_EXISTS(Z4_DIR)
|
||||||
#define HAS_Z4_DIR 1
|
#define HAS_Z4_DIR 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z4_STEP)
|
#if PIN_EXISTS(Z4_STEP)
|
||||||
#define HAS_Z4_STEP 1
|
#define HAS_Z4_STEP 1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z4_MS1)
|
#if PIN_EXISTS(Z4_MS1)
|
||||||
#define HAS_Z4_MS_PINS 1
|
#define HAS_Z4_MS_PINS 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#if PIN_EXISTS(I_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(I))
|
||||||
|
#define HAS_I_ENABLE 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_DIR)
|
||||||
|
#define HAS_I_DIR 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_STEP)
|
||||||
|
#define HAS_I_STEP 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS1)
|
||||||
|
#define HAS_I_MS_PINS 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#if PIN_EXISTS(J_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(J))
|
||||||
|
#define HAS_J_ENABLE 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_DIR)
|
||||||
|
#define HAS_J_DIR 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_STEP)
|
||||||
|
#define HAS_J_STEP 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS1)
|
||||||
|
#define HAS_J_MS_PINS 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#if PIN_EXISTS(K_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(K))
|
||||||
|
#define HAS_K_ENABLE 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_DIR)
|
||||||
|
#define HAS_K_DIR 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_STEP)
|
||||||
|
#define HAS_K_STEP 1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS1)
|
||||||
|
#define HAS_K_MS_PINS 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Extruder steppers and solenoids
|
// Extruder steppers and solenoids
|
||||||
|
@ -1700,7 +1875,7 @@
|
||||||
//
|
//
|
||||||
|
|
||||||
#if HAS_TRINAMIC_CONFIG
|
#if HAS_TRINAMIC_CONFIG
|
||||||
#if ANY(STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_E)
|
#if ANY(STEALTHCHOP_E, STEALTHCHOP_XY, STEALTHCHOP_Z, STEALTHCHOP_I, STEALTHCHOP_J, STEALTHCHOP_K)
|
||||||
#define STEALTHCHOP_ENABLED 1
|
#define STEALTHCHOP_ENABLED 1
|
||||||
#endif
|
#endif
|
||||||
#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
|
#if EITHER(SENSORLESS_HOMING, SENSORLESS_PROBING)
|
||||||
|
@ -1737,6 +1912,65 @@
|
||||||
#if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4)
|
#if defined(Z4_STALL_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z4)
|
||||||
#define Z4_SENSORLESS 1
|
#define Z4_SENSORLESS 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(X)
|
||||||
|
#define X_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(X2)
|
||||||
|
#define X2_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Y)
|
||||||
|
#define Y_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Y2)
|
||||||
|
#define Y2_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Z)
|
||||||
|
#define Z_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Z2)
|
||||||
|
#define Z2_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Z3)
|
||||||
|
#define Z3_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(Z4)
|
||||||
|
#define Z4_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(I)
|
||||||
|
#define I_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(J)
|
||||||
|
#define J_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_STEALTHCHOP(K)
|
||||||
|
#define K_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 0 && AXIS_HAS_STEALTHCHOP(E0)
|
||||||
|
#define E0_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 1 && AXIS_HAS_STEALTHCHOP(E1)
|
||||||
|
#define E1_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 2 && AXIS_HAS_STEALTHCHOP(E2)
|
||||||
|
#define E2_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 3 && AXIS_HAS_STEALTHCHOP(E3)
|
||||||
|
#define E3_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 4 && AXIS_HAS_STEALTHCHOP(E4)
|
||||||
|
#define E4_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 5 && AXIS_HAS_STEALTHCHOP(E5)
|
||||||
|
#define E5_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 6 && AXIS_HAS_STEALTHCHOP(E6)
|
||||||
|
#define E6_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
#if E_STEPPERS > 7 && AXIS_HAS_STEALTHCHOP(E7)
|
||||||
|
#define E7_HAS_STEALTHCHOP 1
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SPI_ENDSTOPS)
|
#if ENABLED(SPI_ENDSTOPS)
|
||||||
#define X_SPI_SENSORLESS X_SENSORLESS
|
#define X_SPI_SENSORLESS X_SENSORLESS
|
||||||
#define Y_SPI_SENSORLESS Y_SENSORLESS
|
#define Y_SPI_SENSORLESS Y_SENSORLESS
|
||||||
|
@ -1766,6 +2000,21 @@
|
||||||
#ifndef Z4_INTERPOLATE
|
#ifndef Z4_INTERPOLATE
|
||||||
#define Z4_INTERPOLATE INTERPOLATE
|
#define Z4_INTERPOLATE INTERPOLATE
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#ifndef I_INTERPOLATE
|
||||||
|
#define I_INTERPOLATE INTERPOLATE
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#ifndef J_INTERPOLATE
|
||||||
|
#define J_INTERPOLATE INTERPOLATE
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#ifndef K_INTERPOLATE
|
||||||
|
#define K_INTERPOLATE INTERPOLATE
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#ifndef E0_INTERPOLATE
|
#ifndef E0_INTERPOLATE
|
||||||
#define E0_INTERPOLATE INTERPOLATE
|
#define E0_INTERPOLATE INTERPOLATE
|
||||||
#endif
|
#endif
|
||||||
|
@ -1799,6 +2048,15 @@
|
||||||
#ifndef Z_SLAVE_ADDRESS
|
#ifndef Z_SLAVE_ADDRESS
|
||||||
#define Z_SLAVE_ADDRESS 0
|
#define Z_SLAVE_ADDRESS 0
|
||||||
#endif
|
#endif
|
||||||
|
#ifndef I_SLAVE_ADDRESS
|
||||||
|
#define I_SLAVE_ADDRESS 0
|
||||||
|
#endif
|
||||||
|
#ifndef J_SLAVE_ADDRESS
|
||||||
|
#define J_SLAVE_ADDRESS 0
|
||||||
|
#endif
|
||||||
|
#ifndef K_SLAVE_ADDRESS
|
||||||
|
#define K_SLAVE_ADDRESS 0
|
||||||
|
#endif
|
||||||
#ifndef X2_SLAVE_ADDRESS
|
#ifndef X2_SLAVE_ADDRESS
|
||||||
#define X2_SLAVE_ADDRESS 0
|
#define X2_SLAVE_ADDRESS 0
|
||||||
#endif
|
#endif
|
||||||
|
@ -1853,6 +2111,10 @@
|
||||||
#define HAS_TMC_SW_SERIAL 1
|
#define HAS_TMC_SW_SERIAL 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !USE_SENSORLESS
|
||||||
|
#undef SENSORLESS_BACKOFF_MM
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Set USING_HW_SERIALn flags for used Serial Ports
|
// Set USING_HW_SERIALn flags for used Serial Ports
|
||||||
//
|
//
|
||||||
|
@ -1972,18 +2234,36 @@
|
||||||
#if _HAS_STOP(X,MAX)
|
#if _HAS_STOP(X,MAX)
|
||||||
#define HAS_X_MAX 1
|
#define HAS_X_MAX 1
|
||||||
#endif
|
#endif
|
||||||
#if _HAS_STOP(Y,MIN)
|
#if HAS_Y_AXIS && _HAS_STOP(Y,MIN)
|
||||||
#define HAS_Y_MIN 1
|
#define HAS_Y_MIN 1
|
||||||
#endif
|
#endif
|
||||||
#if _HAS_STOP(Y,MAX)
|
#if HAS_Y_AXIS && _HAS_STOP(Y,MAX)
|
||||||
#define HAS_Y_MAX 1
|
#define HAS_Y_MAX 1
|
||||||
#endif
|
#endif
|
||||||
#if _HAS_STOP(Z,MIN)
|
#if BOTH(HAS_Z_AXIS, USE_ZMIN_PLUG) && _HAS_STOP(Z,MIN)
|
||||||
#define HAS_Z_MIN 1
|
#define HAS_Z_MIN 1
|
||||||
#endif
|
#endif
|
||||||
#if _HAS_STOP(Z,MAX)
|
#if BOTH(HAS_Z_AXIS, USE_ZMAX_PLUG) && _HAS_STOP(Z,MAX)
|
||||||
#define HAS_Z_MAX 1
|
#define HAS_Z_MAX 1
|
||||||
#endif
|
#endif
|
||||||
|
#if _HAS_STOP(I,MIN)
|
||||||
|
#define HAS_I_MIN 1
|
||||||
|
#endif
|
||||||
|
#if _HAS_STOP(I,MAX)
|
||||||
|
#define HAS_I_MAX 1
|
||||||
|
#endif
|
||||||
|
#if _HAS_STOP(J,MIN)
|
||||||
|
#define HAS_J_MIN 1
|
||||||
|
#endif
|
||||||
|
#if _HAS_STOP(J,MAX)
|
||||||
|
#define HAS_J_MAX 1
|
||||||
|
#endif
|
||||||
|
#if _HAS_STOP(K,MIN)
|
||||||
|
#define HAS_K_MIN 1
|
||||||
|
#endif
|
||||||
|
#if _HAS_STOP(K,MAX)
|
||||||
|
#define HAS_K_MAX 1
|
||||||
|
#endif
|
||||||
#if PIN_EXISTS(X2_MIN)
|
#if PIN_EXISTS(X2_MIN)
|
||||||
#define HAS_X2_MIN 1
|
#define HAS_X2_MIN 1
|
||||||
#endif
|
#endif
|
||||||
|
@ -2365,7 +2645,7 @@
|
||||||
#if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS)
|
#if ANY(HAS_E0_MS_PINS, HAS_E1_MS_PINS, HAS_E2_MS_PINS, HAS_E3_MS_PINS, HAS_E4_MS_PINS, HAS_E5_MS_PINS, HAS_E6_MS_PINS, HAS_E7_MS_PINS)
|
||||||
#define HAS_SOME_E_MS_PINS 1
|
#define HAS_SOME_E_MS_PINS 1
|
||||||
#endif
|
#endif
|
||||||
#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_SOME_E_MS_PINS)
|
#if ANY(HAS_X_MS_PINS, HAS_X2_MS_PINS, HAS_Y_MS_PINS, HAS_Y2_MS_PINS, HAS_SOME_Z_MS_PINS, HAS_I_MS_PINS, HAS_J_MS_PINS, HAS_K_MS_PINS, HAS_SOME_E_MS_PINS)
|
||||||
#define HAS_MICROSTEPS 1
|
#define HAS_MICROSTEPS 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -34,6 +34,10 @@
|
||||||
#error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain."
|
#error "Marlin requires C++11 support (gcc >= 4.7, Arduino IDE >= 1.6.8). Please upgrade your toolchain."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Strings for sanity check messages
|
||||||
|
#define _LINEAR_AXES_STR LINEAR_AXIS_GANG("X ", "Y ", "Z ", "I ", "J ", "K ")
|
||||||
|
#define _LOGICAL_AXES_STR LOGICAL_AXIS_GANG("E ", "X ", "Y ", "Z ", "I ", "J ", "K ")
|
||||||
|
|
||||||
// Make sure macros aren't borked
|
// Make sure macros aren't borked
|
||||||
#define TEST1
|
#define TEST1
|
||||||
#define TEST2 1
|
#define TEST2 1
|
||||||
|
@ -566,6 +570,9 @@
|
||||||
#error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST."
|
#error "NEOPIXEL_BKGD_LED_INDEX is now NEOPIXEL_BKGD_INDEX_FIRST."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
constexpr float sbm[] = AXIS_RELATIVE_MODES;
|
||||||
|
static_assert(COUNT(sbm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _LOGICAL_AXES_STR "elements.");
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Probe temp compensation requirements
|
* Probe temp compensation requirements
|
||||||
*/
|
*/
|
||||||
|
@ -644,14 +651,18 @@
|
||||||
|
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y)
|
||||||
#error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined."
|
#error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined."
|
||||||
#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
#if !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
|
||||||
#error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
|
#error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
|
||||||
#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
|
#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
|
||||||
#error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
|
#error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
|
||||||
#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
|
#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
|
||||||
#error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
|
#error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
|
||||||
#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
|
#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
|
||||||
#error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
|
#error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -704,6 +715,12 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
||||||
#error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN."
|
#error "Enable only one of ENDSTOPPULLUP_Y_MIN or ENDSTOPPULLDOWN_Y_MIN."
|
||||||
#elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN)
|
#elif BOTH(ENDSTOPPULLUP_ZMIN, ENDSTOPPULLDOWN_ZMIN)
|
||||||
#error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN."
|
#error "Enable only one of ENDSTOPPULLUP_Z_MIN or ENDSTOPPULLDOWN_Z_MIN."
|
||||||
|
#elif BOTH(ENDSTOPPULLUP_IMIN, ENDSTOPPULLDOWN_IMIN)
|
||||||
|
#error "Enable only one of ENDSTOPPULLUP_I_MIN or ENDSTOPPULLDOWN_I_MIN."
|
||||||
|
#elif BOTH(ENDSTOPPULLUP_JMIN, ENDSTOPPULLDOWN_JMIN)
|
||||||
|
#error "Enable only one of ENDSTOPPULLUP_J_MIN or ENDSTOPPULLDOWN_J_MIN."
|
||||||
|
#elif BOTH(ENDSTOPPULLUP_KMIN, ENDSTOPPULLDOWN_KMIN)
|
||||||
|
#error "Enable only one of ENDSTOPPULLUP_K_MIN or ENDSTOPPULLDOWN_K_MIN."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -926,6 +943,13 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
||||||
static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS).");
|
static_assert(WITHIN(npp_xyz.z, Z_MIN_POS, Z_MAX_POS), "NOZZLE_PARK_POINT.Z is out of bounds (Z_MIN_POS, Z_MAX_POS).");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Instant Freeze
|
||||||
|
*/
|
||||||
|
#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE)
|
||||||
|
#error "FREEZE_FEATURE requires a FREEZE_PIN to be defined."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Individual axis homing is useless for DELTAS
|
* Individual axis homing is useless for DELTAS
|
||||||
*/
|
*/
|
||||||
|
@ -1266,6 +1290,42 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
||||||
#error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER."
|
#error "To use CHAMBER_LIMIT_SWITCHING you must disable PIDTEMPCHAMBER."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Features that require a min/max/specific LINEAR_AXES
|
||||||
|
*/
|
||||||
|
#if HAS_LEVELING && !HAS_Z_AXIS
|
||||||
|
#error "Leveling in Marlin requires three or more axes, with Z as the vertical axis."
|
||||||
|
#elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS
|
||||||
|
#error "CNC_WORKSPACE_PLANES currently requires LINEAR_AXES >= 3"
|
||||||
|
#elif ENABLED(DIRECT_STEPPING) && LINEAR_AXES > XYZ
|
||||||
|
#error "DIRECT_STEPPING currently requires LINEAR_AXES 3"
|
||||||
|
#elif ENABLED(FOAMCUTTER_XYUV) && LINEAR_AXES < 5
|
||||||
|
#error "FOAMCUTTER_XYUV requires LINEAR_AXES >= 5."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Allow only extra axis codes that do not conflict with G-code parameter names
|
||||||
|
*/
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#if AXIS4_NAME != 'A' && AXIS4_NAME != 'B' && AXIS4_NAME != 'C' && AXIS4_NAME != 'U' && AXIS4_NAME != 'V' && AXIS4_NAME != 'W'
|
||||||
|
#error "AXIS4_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#if AXIS5_NAME == AXIS4_NAME || AXIS5_NAME == AXIS6_NAME
|
||||||
|
#error "AXIS5_NAME must be different from AXIS4_NAME and AXIS6_NAME"
|
||||||
|
#elif AXIS5_NAME != 'A' && AXIS5_NAME != 'B' && AXIS5_NAME != 'C' && AXIS5_NAME != 'U' && AXIS5_NAME != 'V' && AXIS5_NAME != 'W'
|
||||||
|
#error "AXIS5_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#if AXIS6_NAME == AXIS5_NAME || AXIS6_NAME == AXIS4_NAME
|
||||||
|
#error "AXIS6_NAME must be different from AXIS5_NAME and AXIS4_NAME."
|
||||||
|
#elif AXIS6_NAME != 'A' && AXIS6_NAME != 'B' && AXIS6_NAME != 'C' && AXIS6_NAME != 'U' && AXIS6_NAME != 'V' && AXIS6_NAME != 'W'
|
||||||
|
#error "AXIS6_NAME can only be one of 'A', 'B', 'C', 'U', 'V', or 'W'."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Kinematics
|
* Kinematics
|
||||||
*/
|
*/
|
||||||
|
@ -1273,8 +1333,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
||||||
/**
|
/**
|
||||||
* Allow only one kinematic type to be defined
|
* Allow only one kinematic type to be defined
|
||||||
*/
|
*/
|
||||||
#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY)
|
#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, FOAMCUTTER_XYUV)
|
||||||
#error "Please enable only one of DELTA, MORGAN_SCARA, AXEL_TPARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, COREZY, or MARKFORGED_XY."
|
#error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, or FOAMCUTTER_XYUV."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1597,15 +1657,60 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Homing
|
* Homing checks
|
||||||
*/
|
*/
|
||||||
constexpr float hbm[] = HOMING_BUMP_MM;
|
#ifndef HOMING_BUMP_MM
|
||||||
static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM requires one element per linear axis.");
|
#error "Required setting HOMING_BUMP_MM is missing!"
|
||||||
LINEAR_AXIS_CODE(
|
#elif !defined(HOMING_BUMP_DIVISOR)
|
||||||
|
#error "Required setting HOMING_BUMP_DIVISOR is missing!"
|
||||||
|
#else
|
||||||
|
constexpr float hbm[] = HOMING_BUMP_MM, hbd[] = HOMING_BUMP_DIVISOR;
|
||||||
|
static_assert(COUNT(hbm) == LINEAR_AXES, "HOMING_BUMP_MM must have " _LINEAR_AXES_STR "elements (and no others).");
|
||||||
|
LINEAR_AXIS_CODE(
|
||||||
static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."),
|
static_assert(hbm[X_AXIS] >= 0, "HOMING_BUMP_MM.X must be greater than or equal to 0."),
|
||||||
static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."),
|
static_assert(hbm[Y_AXIS] >= 0, "HOMING_BUMP_MM.Y must be greater than or equal to 0."),
|
||||||
static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0.")
|
static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal to 0."),
|
||||||
);
|
static_assert(hbm[I_AXIS] >= 0, "HOMING_BUMP_MM.I must be greater than or equal to 0."),
|
||||||
|
static_assert(hbm[J_AXIS] >= 0, "HOMING_BUMP_MM.J must be greater than or equal to 0."),
|
||||||
|
static_assert(hbm[K_AXIS] >= 0, "HOMING_BUMP_MM.K must be greater than or equal to 0.")
|
||||||
|
);
|
||||||
|
static_assert(COUNT(hbd) == LINEAR_AXES, "HOMING_BUMP_DIVISOR must have " _LINEAR_AXES_STR "elements (and no others).");
|
||||||
|
LINEAR_AXIS_CODE(
|
||||||
|
static_assert(hbd[X_AXIS] >= 1, "HOMING_BUMP_DIVISOR.X must be greater than or equal to 1."),
|
||||||
|
static_assert(hbd[Y_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Y must be greater than or equal to 1."),
|
||||||
|
static_assert(hbd[Z_AXIS] >= 1, "HOMING_BUMP_DIVISOR.Z must be greater than or equal to 1."),
|
||||||
|
static_assert(hbd[I_AXIS] >= 1, "HOMING_BUMP_DIVISOR.I must be greater than or equal to 1."),
|
||||||
|
static_assert(hbd[J_AXIS] >= 1, "HOMING_BUMP_DIVISOR.J must be greater than or equal to 1."),
|
||||||
|
static_assert(hbd[K_AXIS] >= 1, "HOMING_BUMP_DIVISOR.K must be greater than or equal to 1.")
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HOMING_BACKOFF_POST_MM
|
||||||
|
constexpr float hbp[] = HOMING_BACKOFF_POST_MM;
|
||||||
|
static_assert(COUNT(hbp) == LINEAR_AXES, "HOMING_BACKOFF_POST_MM must have " _LINEAR_AXES_STR "elements (and no others).");
|
||||||
|
LINEAR_AXIS_CODE(
|
||||||
|
static_assert(hbp[X_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.X must be greater than or equal to 0."),
|
||||||
|
static_assert(hbp[Y_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Y must be greater than or equal to 0."),
|
||||||
|
static_assert(hbp[Z_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.Z must be greater than or equal to 0."),
|
||||||
|
static_assert(hbp[I_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.I must be greater than or equal to 0."),
|
||||||
|
static_assert(hbp[J_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.J must be greater than or equal to 0."),
|
||||||
|
static_assert(hbp[K_AXIS] >= 0, "HOMING_BACKOFF_POST_MM.K must be greater than or equal to 0.")
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef SENSORLESS_BACKOFF_MM
|
||||||
|
constexpr float sbm[] = SENSORLESS_BACKOFF_MM;
|
||||||
|
static_assert(COUNT(sbm) == LINEAR_AXES, "SENSORLESS_BACKOFF_MM must have " _LINEAR_AXES_STR "elements (and no others).");
|
||||||
|
LINEAR_AXIS_CODE(
|
||||||
|
static_assert(sbm[X_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.X must be greater than or equal to 0."),
|
||||||
|
static_assert(sbm[Y_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Y must be greater than or equal to 0."),
|
||||||
|
static_assert(sbm[Z_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.Z must be greater than or equal to 0."),
|
||||||
|
static_assert(sbm[I_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.I must be greater than or equal to 0."),
|
||||||
|
static_assert(sbm[J_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.J must be greater than or equal to 0."),
|
||||||
|
static_assert(sbm[K_AXIS] >= 0, "SENSORLESS_BACKOFF_MM.K must be greater than or equal to 0.")
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(CODEPENDENT_XY_HOMING)
|
#if ENABLED(CODEPENDENT_XY_HOMING)
|
||||||
#if ENABLED(QUICK_HOME)
|
#if ENABLED(QUICK_HOME)
|
||||||
#error "QUICK_HOME is incompatible with CODEPENDENT_XY_HOMING."
|
#error "QUICK_HOME is incompatible with CODEPENDENT_XY_HOMING."
|
||||||
|
@ -1625,9 +1730,9 @@ LINEAR_AXIS_CODE(
|
||||||
/**
|
/**
|
||||||
* Make sure DISABLE_[XYZ] compatible with selected homing options
|
* Make sure DISABLE_[XYZ] compatible with selected homing options
|
||||||
*/
|
*/
|
||||||
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z)
|
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K)
|
||||||
#if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING)
|
#if EITHER(HOME_AFTER_DEACTIVATE, Z_SAFE_HOMING)
|
||||||
#error "DISABLE_[XYZ] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
|
#error "DISABLE_[XYZIJK] is not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2085,7 +2190,7 @@ LINEAR_AXIS_CODE(
|
||||||
#define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \
|
#define _PLUG_UNUSED_TEST(A,P) (DISABLED(USE_##P##MIN_PLUG, USE_##P##MAX_PLUG) \
|
||||||
&& !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \
|
&& !(ENABLED(A##_DUAL_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) \
|
||||||
&& !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) )
|
&& !(ENABLED(A##_MULTI_ENDSTOPS) && WITHIN(A##2_USE_ENDSTOP, _##P##MAX_, _##P##MIN_)) )
|
||||||
#define _AXIS_PLUG_UNUSED_TEST(A) (_PLUG_UNUSED_TEST(A,X) && _PLUG_UNUSED_TEST(A,Y) && _PLUG_UNUSED_TEST(A,Z))
|
#define _AXIS_PLUG_UNUSED_TEST(A) (1 LINEAR_AXIS_GANG(&& _PLUG_UNUSED_TEST(A,X), && _PLUG_UNUSED_TEST(A,Y), && _PLUG_UNUSED_TEST(A,Z), && _PLUG_UNUSED_TEST(A,I), && _PLUG_UNUSED_TEST(A,J), && _PLUG_UNUSED_TEST(A,K) ) )
|
||||||
|
|
||||||
// A machine with endstops must have a minimum of 3
|
// A machine with endstops must have a minimum of 3
|
||||||
#if HAS_ENDSTOPS
|
#if HAS_ENDSTOPS
|
||||||
|
@ -2098,6 +2203,15 @@ LINEAR_AXIS_CODE(
|
||||||
#if _AXIS_PLUG_UNUSED_TEST(Z)
|
#if _AXIS_PLUG_UNUSED_TEST(Z)
|
||||||
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
|
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && _AXIS_PLUG_UNUSED_TEST(I)
|
||||||
|
#error "You must enable USE_IMIN_PLUG or USE_IMAX_PLUG."
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && _AXIS_PLUG_UNUSED_TEST(J)
|
||||||
|
#error "You must enable USE_JMIN_PLUG or USE_JMAX_PLUG."
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && _AXIS_PLUG_UNUSED_TEST(K)
|
||||||
|
#error "You must enable USE_KMIN_PLUG or USE_KMAX_PLUG."
|
||||||
|
#endif
|
||||||
|
|
||||||
// Delta and Cartesian use 3 homing endstops
|
// Delta and Cartesian use 3 homing endstops
|
||||||
#if NONE(IS_SCARA, SPI_ENDSTOPS)
|
#if NONE(IS_SCARA, SPI_ENDSTOPS)
|
||||||
|
@ -2109,6 +2223,18 @@ LINEAR_AXIS_CODE(
|
||||||
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
|
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
|
||||||
#elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG)
|
#elif Y_HOME_TO_MAX && DISABLED(USE_YMAX_PLUG)
|
||||||
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
|
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
|
||||||
|
#elif LINEAR_AXES >= 4 && I_HOME_TO_MIN && DISABLED(USE_IMIN_PLUG)
|
||||||
|
#error "Enable USE_IMIN_PLUG when homing I to MIN."
|
||||||
|
#elif LINEAR_AXES >= 4 && I_HOME_TO_MAX && DISABLED(USE_IMAX_PLUG)
|
||||||
|
#error "Enable USE_IMAX_PLUG when homing I to MAX."
|
||||||
|
#elif LINEAR_AXES >= 5 && J_HOME_TO_MIN && DISABLED(USE_JMIN_PLUG)
|
||||||
|
#error "Enable USE_JMIN_PLUG when homing J to MIN."
|
||||||
|
#elif LINEAR_AXES >= 5 && J_HOME_TO_MAX && DISABLED(USE_JMAX_PLUG)
|
||||||
|
#error "Enable USE_JMAX_PLUG when homing J to MAX."
|
||||||
|
#elif LINEAR_AXES >= 6 && K_HOME_TO_MIN && DISABLED(USE_KMIN_PLUG)
|
||||||
|
#error "Enable USE_KMIN_PLUG when homing K to MIN."
|
||||||
|
#elif LINEAR_AXES >= 6 && K_HOME_TO_MAX && DISABLED(USE_KMAX_PLUG)
|
||||||
|
#error "Enable USE_KMAX_PLUG when homing K to MAX."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2503,6 +2629,12 @@ LINEAR_AXIS_CODE(
|
||||||
#error "An SPI driven TMC driver on E6 requires E6_CS_PIN."
|
#error "An SPI driven TMC driver on E6 requires E6_CS_PIN."
|
||||||
#elif INVALID_TMC_SPI(E7)
|
#elif INVALID_TMC_SPI(E7)
|
||||||
#error "An SPI driven TMC driver on E7 requires E7_CS_PIN."
|
#error "An SPI driven TMC driver on E7 requires E7_CS_PIN."
|
||||||
|
#elif INVALID_TMC_SPI(I)
|
||||||
|
#error "An SPI driven TMC on I requires I_CS_PIN."
|
||||||
|
#elif INVALID_TMC_SPI(J)
|
||||||
|
#error "An SPI driven TMC on J requires J_CS_PIN."
|
||||||
|
#elif INVALID_TMC_SPI(K)
|
||||||
|
#error "An SPI driven TMC on K requires K_CS_PIN."
|
||||||
#endif
|
#endif
|
||||||
#undef INVALID_TMC_SPI
|
#undef INVALID_TMC_SPI
|
||||||
|
|
||||||
|
@ -2542,6 +2674,12 @@ LINEAR_AXIS_CODE(
|
||||||
#error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
|
#error "TMC2208 or TMC2209 on E6 requires E6_HARDWARE_SERIAL or E6_SERIAL_(RX|TX)_PIN."
|
||||||
#elif INVALID_TMC_UART(E7)
|
#elif INVALID_TMC_UART(E7)
|
||||||
#error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
|
#error "TMC2208 or TMC2209 on E7 requires E7_HARDWARE_SERIAL or E7_SERIAL_(RX|TX)_PIN."
|
||||||
|
#elif LINEAR_AXES >= 4 && INVALID_TMC_UART(I)
|
||||||
|
#error "TMC2208 or TMC2209 on I requires I_HARDWARE_SERIAL or I_SERIAL_(RX|TX)_PIN."
|
||||||
|
#elif LINEAR_AXES >= 5 && INVALID_TMC_UART(J)
|
||||||
|
#error "TMC2208 or TMC2209 on J requires J_HARDWARE_SERIAL or J_SERIAL_(RX|TX)_PIN."
|
||||||
|
#elif LINEAR_AXES >= 6 && INVALID_TMC_UART(K)
|
||||||
|
#error "TMC2208 or TMC2209 on K requires K_HARDWARE_SERIAL or K_SERIAL_(RX|TX)_PIN."
|
||||||
#endif
|
#endif
|
||||||
#undef INVALID_TMC_UART
|
#undef INVALID_TMC_UART
|
||||||
|
|
||||||
|
@ -2565,6 +2703,12 @@ LINEAR_AXIS_CODE(
|
||||||
INVALID_TMC_ADDRESS(Z3);
|
INVALID_TMC_ADDRESS(Z3);
|
||||||
#elif AXIS_DRIVER_TYPE_Z4(TMC2209)
|
#elif AXIS_DRIVER_TYPE_Z4(TMC2209)
|
||||||
INVALID_TMC_ADDRESS(Z4);
|
INVALID_TMC_ADDRESS(Z4);
|
||||||
|
#elif AXIS_DRIVER_TYPE_I(TMC2209)
|
||||||
|
INVALID_TMC_ADDRESS(I);
|
||||||
|
#elif AXIS_DRIVER_TYPE_J(TMC2209)
|
||||||
|
INVALID_TMC_ADDRESS(J);
|
||||||
|
#elif AXIS_DRIVER_TYPE_K(TMC2209)
|
||||||
|
INVALID_TMC_ADDRESS(K);
|
||||||
#elif AXIS_DRIVER_TYPE_E0(TMC2209)
|
#elif AXIS_DRIVER_TYPE_E0(TMC2209)
|
||||||
INVALID_TMC_ADDRESS(E0);
|
INVALID_TMC_ADDRESS(E0);
|
||||||
#elif AXIS_DRIVER_TYPE_E1(TMC2209)
|
#elif AXIS_DRIVER_TYPE_E1(TMC2209)
|
||||||
|
@ -2620,6 +2764,12 @@ LINEAR_AXIS_CODE(
|
||||||
INVALID_TMC_MS(E6)
|
INVALID_TMC_MS(E6)
|
||||||
#elif !TMC_MICROSTEP_IS_VALID(E7)
|
#elif !TMC_MICROSTEP_IS_VALID(E7)
|
||||||
INVALID_TMC_MS(E7)
|
INVALID_TMC_MS(E7)
|
||||||
|
#elif LINEAR_AXES >= 4 && !TMC_MICROSTEP_IS_VALID(I)
|
||||||
|
INVALID_TMC_MS(I)
|
||||||
|
#elif LINEAR_AXES >= 5 && !TMC_MICROSTEP_IS_VALID(J)
|
||||||
|
INVALID_TMC_MS(J)
|
||||||
|
#elif LINEAR_AXES >= 6 && !TMC_MICROSTEP_IS_VALID(K)
|
||||||
|
INVALID_TMC_MS(K)
|
||||||
#endif
|
#endif
|
||||||
#undef INVALID_TMC_MS
|
#undef INVALID_TMC_MS
|
||||||
#undef TMC_MICROSTEP_IS_VALID
|
#undef TMC_MICROSTEP_IS_VALID
|
||||||
|
@ -2640,6 +2790,15 @@ LINEAR_AXIS_CODE(
|
||||||
#define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209)
|
#define X_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(X,TMC2209)
|
||||||
#define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209)
|
#define Y_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Y,TMC2209)
|
||||||
#define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209)
|
#define Z_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(Z,TMC2209)
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define I_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(I,TMC2209)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define J_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(J,TMC2209)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define K_ENDSTOP_INVERTING !AXIS_DRIVER_TYPE(K,TMC2209)
|
||||||
|
#endif
|
||||||
|
|
||||||
#if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS)
|
#if NONE(SPI_ENDSTOPS, ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS)
|
||||||
#if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN)
|
#if X_SENSORLESS && X_HOME_TO_MIN && DISABLED(ENDSTOPPULLUP_XMIN)
|
||||||
|
@ -2654,6 +2813,12 @@ LINEAR_AXIS_CODE(
|
||||||
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN."
|
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMIN (or ENDSTOPPULLUPS) when homing to Z_MIN."
|
||||||
#elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX)
|
#elif Z_SENSORLESS && Z_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_ZMAX)
|
||||||
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX."
|
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_ZMAX (or ENDSTOPPULLUPS) when homing to Z_MAX."
|
||||||
|
#elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_IMAX)
|
||||||
|
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_IMAX (or ENDSTOPPULLUPS) when homing to I_MAX."
|
||||||
|
#elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_JMAX)
|
||||||
|
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_JMAX (or ENDSTOPPULLUPS) when homing to J_MAX."
|
||||||
|
#elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && DISABLED(ENDSTOPPULLUP_KMAX)
|
||||||
|
#error "SENSORLESS_HOMING requires ENDSTOPPULLUP_KMAX (or ENDSTOPPULLUPS) when homing to K_MAX."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2698,6 +2863,42 @@ LINEAR_AXIS_CODE(
|
||||||
#else
|
#else
|
||||||
#error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX."
|
#error "SENSORLESS_HOMING requires Z_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to Z_MAX."
|
||||||
#endif
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MIN && I_MIN_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING
|
||||||
|
#if I_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = true when homing to I_MIN."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires I_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to I_MIN."
|
||||||
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 4 && I_SENSORLESS && I_HOME_TO_MAX && I_MAX_ENDSTOP_INVERTING != I_ENDSTOP_INVERTING
|
||||||
|
#if I_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = true when homing to I_MAX."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires I_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to I_MAX."
|
||||||
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MIN && J_MIN_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING
|
||||||
|
#if J_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = true when homing to J_MIN."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires J_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to J_MIN."
|
||||||
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 5 && J_SENSORLESS && J_HOME_TO_MAX && J_MAX_ENDSTOP_INVERTING != J_ENDSTOP_INVERTING
|
||||||
|
#if J_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = true when homing to J_MAX."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires J_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to J_MAX."
|
||||||
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MIN && K_MIN_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING
|
||||||
|
#if K_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = true when homing to K_MIN."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires K_MIN_ENDSTOP_INVERTING = false when homing TMC2209 to K_MIN."
|
||||||
|
#endif
|
||||||
|
#elif LINEAR_AXES >= 6 && K_SENSORLESS && K_HOME_TO_MAX && K_MAX_ENDSTOP_INVERTING != K_ENDSTOP_INVERTING
|
||||||
|
#if K_ENDSTOP_INVERTING
|
||||||
|
#error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = true when homing to K_MAX."
|
||||||
|
#else
|
||||||
|
#error "SENSORLESS_HOMING requires K_MAX_ENDSTOP_INVERTING = false when homing TMC2209 to K_MAX."
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2712,6 +2913,9 @@ LINEAR_AXIS_CODE(
|
||||||
#undef X_ENDSTOP_INVERTING
|
#undef X_ENDSTOP_INVERTING
|
||||||
#undef Y_ENDSTOP_INVERTING
|
#undef Y_ENDSTOP_INVERTING
|
||||||
#undef Z_ENDSTOP_INVERTING
|
#undef Z_ENDSTOP_INVERTING
|
||||||
|
#undef I_ENDSTOP_INVERTING
|
||||||
|
#undef J_ENDSTOP_INVERTING
|
||||||
|
#undef K_ENDSTOP_INVERTING
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Sensorless probing requirements
|
// Sensorless probing requirements
|
||||||
|
@ -2774,6 +2978,12 @@ LINEAR_AXIS_CODE(
|
||||||
#define CS_COMPARE Z2_CS_PIN
|
#define CS_COMPARE Z2_CS_PIN
|
||||||
#elif IN_CHAIN(Z3)
|
#elif IN_CHAIN(Z3)
|
||||||
#define CS_COMPARE Z3_CS_PIN
|
#define CS_COMPARE Z3_CS_PIN
|
||||||
|
#elif IN_CHAIN(I)
|
||||||
|
#define CS_COMPARE I_CS_PIN
|
||||||
|
#elif IN_CHAIN(J)
|
||||||
|
#define CS_COMPARE J_CS_PIN
|
||||||
|
#elif IN_CHAIN(K)
|
||||||
|
#define CS_COMPARE K_CS_PIN
|
||||||
#elif IN_CHAIN(E0)
|
#elif IN_CHAIN(E0)
|
||||||
#define CS_COMPARE E0_CS_PIN
|
#define CS_COMPARE E0_CS_PIN
|
||||||
#elif IN_CHAIN(E1)
|
#elif IN_CHAIN(E1)
|
||||||
|
@ -2793,6 +3003,7 @@ LINEAR_AXIS_CODE(
|
||||||
#endif
|
#endif
|
||||||
#define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE)
|
#define BAD_CS_PIN(A) (IN_CHAIN(A) && A##_CS_PIN != CS_COMPARE)
|
||||||
#if BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \
|
#if BAD_CS_PIN(X ) || BAD_CS_PIN(Y ) || BAD_CS_PIN(Z ) || BAD_CS_PIN(X2) || BAD_CS_PIN(Y2) || BAD_CS_PIN(Z2) || BAD_CS_PIN(Z3) || BAD_CS_PIN(Z4) \
|
||||||
|
|| BAD_CS_PIN(I) || BAD_CS_PIN(J) || BAD_CS_PIN(K) \
|
||||||
|| BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7)
|
|| BAD_CS_PIN(E0) || BAD_CS_PIN(E1) || BAD_CS_PIN(E2) || BAD_CS_PIN(E3) || BAD_CS_PIN(E4) || BAD_CS_PIN(E5) || BAD_CS_PIN(E6) || BAD_CS_PIN(E7)
|
||||||
#error "All chained TMC drivers must use the same CS pin."
|
#error "All chained TMC drivers must use the same CS pin."
|
||||||
#endif
|
#endif
|
||||||
|
@ -2803,6 +3014,13 @@ LINEAR_AXIS_CODE(
|
||||||
#endif
|
#endif
|
||||||
#undef IN_CHAIN
|
#undef IN_CHAIN
|
||||||
|
|
||||||
|
/**
|
||||||
|
* L64XX requirement
|
||||||
|
*/
|
||||||
|
#if HAS_L64XX && LINEAR_AXES >= 4
|
||||||
|
#error "L64XX requires LINEAR_AXES 3. Homing with L64XX is not yet implemented for LINEAR_AXES > 3."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Digipot requirement
|
* Digipot requirement
|
||||||
*/
|
*/
|
||||||
|
@ -2820,43 +3038,48 @@ LINEAR_AXIS_CODE(
|
||||||
*/
|
*/
|
||||||
constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
|
constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
|
||||||
sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
|
sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
|
||||||
sanity_arr_3[] = DEFAULT_MAX_ACCELERATION;
|
sanity_arr_3[] = DEFAULT_MAX_ACCELERATION,
|
||||||
|
sanity_arr_7[] = HOMING_FEEDRATE_MM_M;
|
||||||
|
|
||||||
#define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0)
|
#define _ARR_TEST(N,I) (sanity_arr_##N[_MIN(I,int(COUNT(sanity_arr_##N))-1)] > 0)
|
||||||
#if HAS_MULTI_EXTRUDER
|
#if HAS_MULTI_EXTRUDER
|
||||||
#define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)"
|
#define _EXTRA_NOTE " (Did you forget to enable DISTINCT_E_FACTORS?)"
|
||||||
#elif EXTRUDERS == 0
|
|
||||||
#define _EXTRA_NOTE " (Note: EXTRUDERS is set to 0.)"
|
|
||||||
#else
|
#else
|
||||||
#define _EXTRA_NOTE ""
|
#define _EXTRA_NOTE " (Should be " STRINGIFY(LINEAR_AXES) "+" STRINGIFY(E_STEPPERS) ")"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_1) >= LOGICAL_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
|
static_assert(COUNT(sanity_arr_1) <= DISTINCT_AXES, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements." _EXTRA_NOTE);
|
||||||
static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2)
|
static_assert( _ARR_TEST(1,0) && _ARR_TEST(1,1) && _ARR_TEST(1,2)
|
||||||
&& _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5)
|
&& _ARR_TEST(1,3) && _ARR_TEST(1,4) && _ARR_TEST(1,5)
|
||||||
&& _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8),
|
&& _ARR_TEST(1,6) && _ARR_TEST(1,7) && _ARR_TEST(1,8),
|
||||||
"DEFAULT_AXIS_STEPS_PER_UNIT values must be positive.");
|
"DEFAULT_AXIS_STEPS_PER_UNIT values must be positive.");
|
||||||
|
|
||||||
static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_2) >= LOGICAL_AXES, "DEFAULT_MAX_FEEDRATE requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
|
static_assert(COUNT(sanity_arr_2) <= DISTINCT_AXES, "DEFAULT_MAX_FEEDRATE has too many elements." _EXTRA_NOTE);
|
||||||
static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2)
|
static_assert( _ARR_TEST(2,0) && _ARR_TEST(2,1) && _ARR_TEST(2,2)
|
||||||
&& _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5)
|
&& _ARR_TEST(2,3) && _ARR_TEST(2,4) && _ARR_TEST(2,5)
|
||||||
&& _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8),
|
&& _ARR_TEST(2,6) && _ARR_TEST(2,7) && _ARR_TEST(2,8),
|
||||||
"DEFAULT_MAX_FEEDRATE values must be positive.");
|
"DEFAULT_MAX_FEEDRATE values must be positive.");
|
||||||
|
|
||||||
static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_3) >= LOGICAL_AXES, "DEFAULT_MAX_ACCELERATION requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
|
static_assert(COUNT(sanity_arr_3) <= DISTINCT_AXES, "DEFAULT_MAX_ACCELERATION has too many elements." _EXTRA_NOTE);
|
||||||
static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
&& _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
|
&& _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
|
||||||
&& _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
|
&& _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
|
||||||
"DEFAULT_MAX_ACCELERATION values must be positive.");
|
"DEFAULT_MAX_ACCELERATION values must be positive.");
|
||||||
|
|
||||||
|
static_assert(COUNT(sanity_arr_7) == LINEAR_AXES, "HOMING_FEEDRATE_MM_M requires " _LINEAR_AXES_STR "elements (and no others).");
|
||||||
|
static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
|
&& _ARR_TEST(3,3) && _ARR_TEST(3,4) && _ARR_TEST(3,5)
|
||||||
|
&& _ARR_TEST(3,6) && _ARR_TEST(3,7) && _ARR_TEST(3,8),
|
||||||
|
"HOMING_FEEDRATE_MM_M values must be positive.");
|
||||||
|
|
||||||
#if ENABLED(LIMITED_MAX_ACCEL_EDITING)
|
#if ENABLED(LIMITED_MAX_ACCEL_EDITING)
|
||||||
#ifdef MAX_ACCEL_EDIT_VALUES
|
#ifdef MAX_ACCEL_EDIT_VALUES
|
||||||
constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES;
|
constexpr float sanity_arr_4[] = MAX_ACCEL_EDIT_VALUES;
|
||||||
static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_4) >= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
|
static_assert(COUNT(sanity_arr_4) <= LOGICAL_AXES, "MAX_ACCEL_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
|
||||||
static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2)
|
static_assert( _ARR_TEST(4,0) && _ARR_TEST(4,1) && _ARR_TEST(4,2)
|
||||||
&& _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5)
|
&& _ARR_TEST(4,3) && _ARR_TEST(4,4) && _ARR_TEST(4,5)
|
||||||
&& _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8),
|
&& _ARR_TEST(4,6) && _ARR_TEST(4,7) && _ARR_TEST(4,8),
|
||||||
|
@ -2867,8 +3090,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
#if ENABLED(LIMITED_MAX_FR_EDITING)
|
#if ENABLED(LIMITED_MAX_FR_EDITING)
|
||||||
#ifdef MAX_FEEDRATE_EDIT_VALUES
|
#ifdef MAX_FEEDRATE_EDIT_VALUES
|
||||||
constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES;
|
constexpr float sanity_arr_5[] = MAX_FEEDRATE_EDIT_VALUES;
|
||||||
static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_5) >= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
|
static_assert(COUNT(sanity_arr_5) <= LOGICAL_AXES, "MAX_FEEDRATE_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
|
||||||
static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2)
|
static_assert( _ARR_TEST(5,0) && _ARR_TEST(5,1) && _ARR_TEST(5,2)
|
||||||
&& _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5)
|
&& _ARR_TEST(5,3) && _ARR_TEST(5,4) && _ARR_TEST(5,5)
|
||||||
&& _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8),
|
&& _ARR_TEST(5,6) && _ARR_TEST(5,7) && _ARR_TEST(5,8),
|
||||||
|
@ -2879,8 +3102,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
#if ENABLED(LIMITED_JERK_EDITING)
|
#if ENABLED(LIMITED_JERK_EDITING)
|
||||||
#ifdef MAX_JERK_EDIT_VALUES
|
#ifdef MAX_JERK_EDIT_VALUES
|
||||||
constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES;
|
constexpr float sanity_arr_6[] = MAX_JERK_EDIT_VALUES;
|
||||||
static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires X, Y, Z and E elements.");
|
static_assert(COUNT(sanity_arr_6) >= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES requires " _LOGICAL_AXES_STR "elements.");
|
||||||
static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. X, Y, Z and E elements only.");
|
static_assert(COUNT(sanity_arr_6) <= LOGICAL_AXES, "MAX_JERK_EDIT_VALUES has too many elements. " _LOGICAL_AXES_STR "elements only.");
|
||||||
static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2)
|
static_assert( _ARR_TEST(6,0) && _ARR_TEST(6,1) && _ARR_TEST(6,2)
|
||||||
&& _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5)
|
&& _ARR_TEST(6,3) && _ARR_TEST(6,4) && _ARR_TEST(6,5)
|
||||||
&& _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8),
|
&& _ARR_TEST(6,6) && _ARR_TEST(6,7) && _ARR_TEST(6,8),
|
||||||
|
@ -3280,6 +3503,22 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
#if _BAD_DRIVER(Z)
|
#if _BAD_DRIVER(Z)
|
||||||
#error "Z_DRIVER_TYPE is not recognized."
|
#error "Z_DRIVER_TYPE is not recognized."
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#if _BAD_DRIVER(I)
|
||||||
|
#error "I_DRIVER_TYPE is not recognized."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#if _BAD_DRIVER(J)
|
||||||
|
#error "J_DRIVER_TYPE is not recognized."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#if _BAD_DRIVER(K)
|
||||||
|
#error "K_DRIVER_TYPE is not recognized."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if _BAD_DRIVER(X2)
|
#if _BAD_DRIVER(X2)
|
||||||
#error "X2_DRIVER_TYPE is not recognized."
|
#error "X2_DRIVER_TYPE is not recognized."
|
||||||
#endif
|
#endif
|
||||||
|
@ -3323,7 +3562,5 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
|
||||||
|
|
||||||
// Misc. Cleanup
|
// Misc. Cleanup
|
||||||
#undef _TEST_PWM
|
#undef _TEST_PWM
|
||||||
|
#undef _LINEAR_AXES_STR
|
||||||
#if ENABLED(FREEZE_FEATURE) && !PIN_EXISTS(FREEZE)
|
#undef _LOGICAL_AXES_STR
|
||||||
#error "FREEZE_FEATURE requires a FREEZE_PIN to be defined."
|
|
||||||
#endif
|
|
||||||
|
|
|
@ -52,7 +52,7 @@
|
||||||
* to alert users to major changes.
|
* to alert users to major changes.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define MARLIN_HEX_VERSION 02000801
|
#define MARLIN_HEX_VERSION 02000900
|
||||||
#ifndef REQUIRED_CONFIGURATION_H_VERSION
|
#ifndef REQUIRED_CONFIGURATION_H_VERSION
|
||||||
#define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION
|
#define REQUIRED_CONFIGURATION_H_VERSION MARLIN_HEX_VERSION
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1235,7 +1235,7 @@ inline ENCODER_DiffState get_encoder_state() {
|
||||||
void HMI_Plan_Move(const feedRate_t fr_mm_s) {
|
void HMI_Plan_Move(const feedRate_t fr_mm_s) {
|
||||||
if (!planner.is_full()) {
|
if (!planner.is_full()) {
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
planner.buffer_line(current_position, fr_mm_s, active_extruder);
|
planner.buffer_line(current_position, fr_mm_s);
|
||||||
DWIN_UpdateLCD();
|
DWIN_UpdateLCD();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -697,13 +697,13 @@ const struct DGUS_VP_Variable ListOfVP[] PROGMEM = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting
|
#if ENABLED(SENSORLESS_HOMING) // TMC SENSORLESS Setting
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
VPHELPER(VP_TMC_X_STEP, &tmc_step.x, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
VPHELPER(VP_TMC_Y_STEP, &tmc_step.y, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
VPHELPER(VP_TMC_Z_STEP, &tmc_step.z, ScreenHandler.TMC_ChangeConfig, ScreenHandler.DGUSLCD_SendTMCStepValue),
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -59,19 +59,19 @@ extern xyz_int_t tmc_step;
|
||||||
|
|
||||||
extern uint16_t lcd_default_light;
|
extern uint16_t lcd_default_light;
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
extern uint16_t tmc_x_current;
|
extern uint16_t tmc_x_current;
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
extern uint16_t tmc_y_current;
|
extern uint16_t tmc_y_current;
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
extern uint16_t tmc_z_current;
|
extern uint16_t tmc_z_current;
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
#if E0_HAS_STEALTHCHOP
|
||||||
extern uint16_t tmc_e0_current;
|
extern uint16_t tmc_e0_current;
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
#if E1_HAS_STEALTHCHOP
|
||||||
extern uint16_t tmc_e1_current;
|
extern uint16_t tmc_e1_current;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -134,15 +134,15 @@ void DGUSScreenHandler::DGUSLCD_SendStringToDisplay_Language_MKS(DGUS_VP_Variabl
|
||||||
|
|
||||||
void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) {
|
void DGUSScreenHandler::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) {
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
tmc_step.x = stepperX.homing_threshold();
|
tmc_step.x = stepperX.homing_threshold();
|
||||||
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
tmc_step.y = stepperY.homing_threshold();
|
tmc_step.y = stepperY.homing_threshold();
|
||||||
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
tmc_step.z = stepperZ.homing_threshold();
|
tmc_step.z = stepperZ.homing_threshold();
|
||||||
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
dgusdisplay.WriteVariable(var.VP, *(int16_t*)var.memadr);
|
||||||
#endif
|
#endif
|
||||||
|
@ -659,7 +659,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
|
||||||
switch (var.VP) {
|
switch (var.VP) {
|
||||||
case VP_TMC_X_STEP:
|
case VP_TMC_X_STEP:
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
stepperX.homing_threshold(mks_min(tmc_value, 255));
|
stepperX.homing_threshold(mks_min(tmc_value, 255));
|
||||||
settings.save();
|
settings.save();
|
||||||
//tmc_step.x = stepperX.homing_threshold();
|
//tmc_step.x = stepperX.homing_threshold();
|
||||||
|
@ -668,7 +668,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
|
||||||
break;
|
break;
|
||||||
case VP_TMC_Y_STEP:
|
case VP_TMC_Y_STEP:
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
stepperY.homing_threshold(mks_min(tmc_value, 255));
|
stepperY.homing_threshold(mks_min(tmc_value, 255));
|
||||||
settings.save();
|
settings.save();
|
||||||
//tmc_step.y = stepperY.homing_threshold();
|
//tmc_step.y = stepperY.homing_threshold();
|
||||||
|
@ -677,7 +677,7 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
|
||||||
break;
|
break;
|
||||||
case VP_TMC_Z_STEP:
|
case VP_TMC_Z_STEP:
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
stepperZ.homing_threshold(mks_min(tmc_value, 255));
|
stepperZ.homing_threshold(mks_min(tmc_value, 255));
|
||||||
settings.save();
|
settings.save();
|
||||||
//tmc_step.z = stepperZ.homing_threshold();
|
//tmc_step.z = stepperZ.homing_threshold();
|
||||||
|
@ -737,15 +737,9 @@ void DGUSScreenHandler::TMC_ChangeConfig(DGUS_VP_Variable &var, void *val_ptr) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold());
|
||||||
tmc_step.x = stepperX.homing_threshold();
|
TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold());
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
|
||||||
tmc_step.y = stepperY.homing_threshold();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
|
||||||
tmc_step.z = stepperZ.homing_threshold();
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1419,15 +1413,9 @@ bool DGUSScreenHandler::loop() {
|
||||||
if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) {
|
if (!booted && ELAPSED(ms, TERN(USE_MKS_GREEN_UI, 1000, BOOTSCREEN_TIMEOUT))) {
|
||||||
booted = true;
|
booted = true;
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, tmc_step.x = stepperX.homing_threshold());
|
||||||
tmc_step.x = stepperX.homing_threshold();
|
TERN_(Y_HAS_STEALTHCHOP, tmc_step.y = stepperY.homing_threshold());
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, tmc_step.z = stepperZ.homing_threshold());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
|
||||||
tmc_step.y = stepperY.homing_threshold();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
|
||||||
tmc_step.z = stepperZ.homing_threshold();
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||||
|
|
|
@ -60,32 +60,32 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) {
|
||||||
)
|
)
|
||||||
.text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS))
|
.text(BTN_POS(1,1), BTN_SIZE(6,1), GET_TEXT_F(MSG_LCD_ENDSTOPS))
|
||||||
.font(font_tiny);
|
.font(font_tiny);
|
||||||
#if PIN_EXISTS(X_MAX)
|
#if HAS_X_MAX
|
||||||
PIN_ENABLED (1, 2, PSTR(STR_X_MAX), X_MAX, X_MAX_ENDSTOP_INVERTING)
|
PIN_ENABLED (1, 2, PSTR(STR_X_MAX), X_MAX, X_MAX_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(1, 2, PSTR(STR_X_MAX), X_MAX)
|
PIN_DISABLED(1, 2, PSTR(STR_X_MAX), X_MAX)
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MAX)
|
#if HAS_Y_MAX
|
||||||
PIN_ENABLED (3, 2, PSTR(STR_Y_MAX), Y_MAX, Y_MAX_ENDSTOP_INVERTING)
|
PIN_ENABLED (3, 2, PSTR(STR_Y_MAX), Y_MAX, Y_MAX_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(3, 2, PSTR(STR_Y_MAX), Y_MAX)
|
PIN_DISABLED(3, 2, PSTR(STR_Y_MAX), Y_MAX)
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MAX)
|
#if HAS_Z_MAX
|
||||||
PIN_ENABLED (5, 2, PSTR(STR_Z_MAX), Z_MAX, Z_MAX_ENDSTOP_INVERTING)
|
PIN_ENABLED (5, 2, PSTR(STR_Z_MAX), Z_MAX, Z_MAX_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(5, 2, PSTR(STR_Z_MAX), Z_MAX)
|
PIN_DISABLED(5, 2, PSTR(STR_Z_MAX), Z_MAX)
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(X_MIN)
|
#if HAS_X_MIN
|
||||||
PIN_ENABLED (1, 3, PSTR(STR_X_MIN), X_MIN, X_MIN_ENDSTOP_INVERTING)
|
PIN_ENABLED (1, 3, PSTR(STR_X_MIN), X_MIN, X_MIN_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(1, 3, PSTR(STR_X_MIN), X_MIN)
|
PIN_DISABLED(1, 3, PSTR(STR_X_MIN), X_MIN)
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MIN)
|
#if HAS_Y_MIN
|
||||||
PIN_ENABLED (3, 3, PSTR(STR_Y_MIN), Y_MIN, Y_MIN_ENDSTOP_INVERTING)
|
PIN_ENABLED (3, 3, PSTR(STR_Y_MIN), Y_MIN, Y_MIN_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(3, 3, PSTR(STR_Y_MIN), Y_MIN)
|
PIN_DISABLED(3, 3, PSTR(STR_Y_MIN), Y_MIN)
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MIN)
|
#if HAS_Z_MIN
|
||||||
PIN_ENABLED (5, 3, PSTR(STR_Z_MIN), Z_MIN, Z_MIN_ENDSTOP_INVERTING)
|
PIN_ENABLED (5, 3, PSTR(STR_Z_MIN), Z_MIN, Z_MIN_ENDSTOP_INVERTING)
|
||||||
#else
|
#else
|
||||||
PIN_DISABLED(5, 3, PSTR(STR_Z_MIN), Z_MIN)
|
PIN_DISABLED(5, 3, PSTR(STR_Z_MIN), Z_MIN)
|
||||||
|
|
|
@ -68,30 +68,20 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
|
||||||
draw_return_ui();
|
draw_return_ui();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
case ID_TMC_MODE_X:
|
case ID_TMC_MODE_X: toggle_chop(stepperX, buttonXState); break;
|
||||||
toggle_chop(stepperX, buttonXState);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
case ID_TMC_MODE_Y:
|
case ID_TMC_MODE_Y: toggle_chop(stepperY, buttonYState); break;
|
||||||
toggle_chop(stepperY, buttonYState);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
case ID_TMC_MODE_Z:
|
case ID_TMC_MODE_Z: toggle_chop(stepperZ, buttonZState); break;
|
||||||
toggle_chop(stepperZ, buttonZState);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
#if E0_HAS_STEALTHCHOP
|
||||||
case ID_TMC_MODE_E0:
|
case ID_TMC_MODE_E0: toggle_chop(stepperE0, buttonE0State); break;
|
||||||
toggle_chop(stepperE0, buttonE0State);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
#if E1_HAS_STEALTHCHOP
|
||||||
case ID_TMC_MODE_E1:
|
case ID_TMC_MODE_E1: toggle_chop(stepperE1, buttonE1State); break;
|
||||||
toggle_chop(stepperE1, buttonE1State);
|
|
||||||
break;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
case ID_TMC_MODE_UP:
|
case ID_TMC_MODE_UP:
|
||||||
|
@ -113,21 +103,11 @@ void lv_draw_tmc_step_mode_settings() {
|
||||||
scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle);
|
scr = lv_screen_create(TMC_MODE_UI, machine_menu.TmcStepModeConfTitle);
|
||||||
|
|
||||||
bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false;
|
bool stealth_X = false, stealth_Y = false, stealth_Z = false, stealth_E0 = false, stealth_E1 = false;
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, stealth_X = stepperX.get_stealthChop());
|
||||||
stealth_X = stepperX.get_stealthChop();
|
TERN_(Y_HAS_STEALTHCHOP, stealth_Y = stepperY.get_stealthChop());
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, stealth_Z = stepperZ.get_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(E0_HAS_STEALTHCHOP, stealth_E0 = stepperE0.get_stealthChop());
|
||||||
stealth_Y = stepperY.get_stealthChop();
|
TERN_(E1_HAS_STEALTHCHOP, stealth_E1 = stepperE1.get_stealthChop());
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
|
||||||
stealth_Z = stepperZ.get_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
stealth_E0 = stepperE0.get_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
stealth_E1 = stepperE1.get_stealthChop();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (!uiCfg.para_ui_page) {
|
if (!uiCfg.para_ui_page) {
|
||||||
buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X);
|
buttonXState = lv_screen_menu_item_onoff(scr, machine_menu.X_StepMode, PARA_UI_POS_X, PARA_UI_POS_Y, event_handler, ID_TMC_MODE_X, 0, stealth_X);
|
||||||
|
|
|
@ -72,6 +72,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X");
|
PROGMEM Language_Str MSG_AUTO_HOME_X = _UxGT("Home X");
|
||||||
PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y");
|
PROGMEM Language_Str MSG_AUTO_HOME_Y = _UxGT("Home Y");
|
||||||
PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z");
|
PROGMEM Language_Str MSG_AUTO_HOME_Z = _UxGT("Home Z");
|
||||||
|
PROGMEM Language_Str MSG_AUTO_HOME_I = _UxGT("Home ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_AUTO_HOME_J = _UxGT("Home ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_AUTO_HOME_K = _UxGT("Home ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align");
|
PROGMEM Language_Str MSG_AUTO_Z_ALIGN = _UxGT("Auto Z-Align");
|
||||||
PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i");
|
PROGMEM Language_Str MSG_ITERATION = _UxGT("G34 Iteration: %i");
|
||||||
PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!");
|
PROGMEM Language_Str MSG_DECREASING_ACCURACY = _UxGT("Accuracy Decreasing!");
|
||||||
|
@ -85,6 +88,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X");
|
PROGMEM Language_Str MSG_HOME_OFFSET_X = _UxGT("Home Offset X");
|
||||||
PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y");
|
PROGMEM Language_Str MSG_HOME_OFFSET_Y = _UxGT("Home Offset Y");
|
||||||
PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z");
|
PROGMEM Language_Str MSG_HOME_OFFSET_Z = _UxGT("Home Offset Z");
|
||||||
|
PROGMEM Language_Str MSG_HOME_OFFSET_I = _UxGT("Home Offset ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_HOME_OFFSET_J = _UxGT("Home Offset ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_HOME_OFFSET_K = _UxGT("Home Offset ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied");
|
PROGMEM Language_Str MSG_HOME_OFFSETS_APPLIED = _UxGT("Offsets Applied");
|
||||||
PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin");
|
PROGMEM Language_Str MSG_SET_ORIGIN = _UxGT("Set Origin");
|
||||||
PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming");
|
PROGMEM Language_Str MSG_ASSISTED_TRAMMING = _UxGT("Assisted Tramming");
|
||||||
|
@ -265,6 +271,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X");
|
PROGMEM Language_Str MSG_MOVE_X = _UxGT("Move X");
|
||||||
PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y");
|
PROGMEM Language_Str MSG_MOVE_Y = _UxGT("Move Y");
|
||||||
PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z");
|
PROGMEM Language_Str MSG_MOVE_Z = _UxGT("Move Z");
|
||||||
|
PROGMEM Language_Str MSG_MOVE_I = _UxGT("Move ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_MOVE_J = _UxGT("Move ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_MOVE_K = _UxGT("Move ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder");
|
PROGMEM Language_Str MSG_MOVE_E = _UxGT("Extruder");
|
||||||
PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *");
|
PROGMEM Language_Str MSG_MOVE_EN = _UxGT("Extruder *");
|
||||||
PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold");
|
PROGMEM Language_Str MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold");
|
||||||
|
@ -329,12 +338,18 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk");
|
PROGMEM Language_Str MSG_VA_JERK = _UxGT("V") LCD_STR_A _UxGT("-Jerk");
|
||||||
PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk");
|
PROGMEM Language_Str MSG_VB_JERK = _UxGT("V") LCD_STR_B _UxGT("-Jerk");
|
||||||
PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk");
|
PROGMEM Language_Str MSG_VC_JERK = _UxGT("V") LCD_STR_C _UxGT("-Jerk");
|
||||||
|
PROGMEM Language_Str MSG_VI_JERK = _UxGT("V") LCD_STR_I _UxGT("-Jerk");
|
||||||
|
PROGMEM Language_Str MSG_VJ_JERK = _UxGT("V") LCD_STR_J _UxGT("-Jerk");
|
||||||
|
PROGMEM Language_Str MSG_VK_JERK = _UxGT("V") LCD_STR_K _UxGT("-Jerk");
|
||||||
PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk");
|
PROGMEM Language_Str MSG_VE_JERK = _UxGT("Ve-Jerk");
|
||||||
PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev");
|
PROGMEM Language_Str MSG_JUNCTION_DEVIATION = _UxGT("Junction Dev");
|
||||||
PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity");
|
PROGMEM Language_Str MSG_VELOCITY = _UxGT("Velocity");
|
||||||
PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A;
|
PROGMEM Language_Str MSG_VMAX_A = _UxGT("Vmax ") LCD_STR_A;
|
||||||
PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B;
|
PROGMEM Language_Str MSG_VMAX_B = _UxGT("Vmax ") LCD_STR_B;
|
||||||
PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C;
|
PROGMEM Language_Str MSG_VMAX_C = _UxGT("Vmax ") LCD_STR_C;
|
||||||
|
PROGMEM Language_Str MSG_VMAX_I = _UxGT("Vmax ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_VMAX_J = _UxGT("Vmax ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_VMAX_K = _UxGT("Vmax ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E;
|
PROGMEM Language_Str MSG_VMAX_E = _UxGT("Vmax ") LCD_STR_E;
|
||||||
PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *");
|
PROGMEM Language_Str MSG_VMAX_EN = _UxGT("Vmax *");
|
||||||
PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin");
|
PROGMEM Language_Str MSG_VMIN = _UxGT("Vmin");
|
||||||
|
@ -343,6 +358,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A;
|
PROGMEM Language_Str MSG_AMAX_A = _UxGT("Amax ") LCD_STR_A;
|
||||||
PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B;
|
PROGMEM Language_Str MSG_AMAX_B = _UxGT("Amax ") LCD_STR_B;
|
||||||
PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C;
|
PROGMEM Language_Str MSG_AMAX_C = _UxGT("Amax ") LCD_STR_C;
|
||||||
|
PROGMEM Language_Str MSG_AMAX_I = _UxGT("Amax ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_AMAX_J = _UxGT("Amax ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_AMAX_K = _UxGT("Amax ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E;
|
PROGMEM Language_Str MSG_AMAX_E = _UxGT("Amax ") LCD_STR_E;
|
||||||
PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *");
|
PROGMEM Language_Str MSG_AMAX_EN = _UxGT("Amax *");
|
||||||
PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract");
|
PROGMEM Language_Str MSG_A_RETRACT = _UxGT("A-Retract");
|
||||||
|
@ -353,6 +371,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm");
|
PROGMEM Language_Str MSG_A_STEPS = LCD_STR_A _UxGT(" Steps/mm");
|
||||||
PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm");
|
PROGMEM Language_Str MSG_B_STEPS = LCD_STR_B _UxGT(" Steps/mm");
|
||||||
PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm");
|
PROGMEM Language_Str MSG_C_STEPS = LCD_STR_C _UxGT(" Steps/mm");
|
||||||
|
PROGMEM Language_Str MSG_I_STEPS = LCD_STR_I _UxGT(" Steps/mm");
|
||||||
|
PROGMEM Language_Str MSG_J_STEPS = LCD_STR_J _UxGT(" Steps/mm");
|
||||||
|
PROGMEM Language_Str MSG_K_STEPS = LCD_STR_K _UxGT(" Steps/mm");
|
||||||
PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm");
|
PROGMEM Language_Str MSG_E_STEPS = _UxGT("E steps/mm");
|
||||||
PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm");
|
PROGMEM Language_Str MSG_EN_STEPS = _UxGT("* Steps/mm");
|
||||||
PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature");
|
PROGMEM Language_Str MSG_TEMPERATURE = _UxGT("Temperature");
|
||||||
|
@ -486,6 +507,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X");
|
PROGMEM Language_Str MSG_BABYSTEP_X = _UxGT("Babystep X");
|
||||||
PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y");
|
PROGMEM Language_Str MSG_BABYSTEP_Y = _UxGT("Babystep Y");
|
||||||
PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z");
|
PROGMEM Language_Str MSG_BABYSTEP_Z = _UxGT("Babystep Z");
|
||||||
|
PROGMEM Language_Str MSG_BABYSTEP_I = _UxGT("Babystep ") LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_BABYSTEP_J = _UxGT("Babystep ") LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_BABYSTEP_K = _UxGT("Babystep ") LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total");
|
PROGMEM Language_Str MSG_BABYSTEP_TOTAL = _UxGT("Total");
|
||||||
PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort");
|
PROGMEM Language_Str MSG_ENDSTOP_ABORT = _UxGT("Endstop Abort");
|
||||||
PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed");
|
PROGMEM Language_Str MSG_HEATING_FAILED_LCD = _UxGT("Heating Failed");
|
||||||
|
@ -566,6 +590,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %");
|
PROGMEM Language_Str MSG_DAC_PERCENT_X = _UxGT("X Driver %");
|
||||||
PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %");
|
PROGMEM Language_Str MSG_DAC_PERCENT_Y = _UxGT("Y Driver %");
|
||||||
PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %");
|
PROGMEM Language_Str MSG_DAC_PERCENT_Z = _UxGT("Z Driver %");
|
||||||
|
PROGMEM Language_Str MSG_DAC_PERCENT_I = _UxGT("I Driver %");
|
||||||
|
PROGMEM Language_Str MSG_DAC_PERCENT_J = _UxGT("J Driver %");
|
||||||
|
PROGMEM Language_Str MSG_DAC_PERCENT_K = _UxGT("K Driver %");
|
||||||
PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %");
|
PROGMEM Language_Str MSG_DAC_PERCENT_E = _UxGT("E Driver %");
|
||||||
PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR");
|
PROGMEM Language_Str MSG_ERROR_TMC = _UxGT("TMC CONNECTION ERROR");
|
||||||
PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write");
|
PROGMEM Language_Str MSG_DAC_EEPROM_WRITE = _UxGT("DAC EEPROM Write");
|
||||||
|
@ -683,6 +710,9 @@ namespace Language_en {
|
||||||
PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A;
|
PROGMEM Language_Str MSG_BACKLASH_A = LCD_STR_A;
|
||||||
PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B;
|
PROGMEM Language_Str MSG_BACKLASH_B = LCD_STR_B;
|
||||||
PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C;
|
PROGMEM Language_Str MSG_BACKLASH_C = LCD_STR_C;
|
||||||
|
PROGMEM Language_Str MSG_BACKLASH_I = LCD_STR_I;
|
||||||
|
PROGMEM Language_Str MSG_BACKLASH_J = LCD_STR_J;
|
||||||
|
PROGMEM Language_Str MSG_BACKLASH_K = LCD_STR_K;
|
||||||
PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction");
|
PROGMEM Language_Str MSG_BACKLASH_CORRECTION = _UxGT("Correction");
|
||||||
PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing");
|
PROGMEM Language_Str MSG_BACKLASH_SMOOTHING = _UxGT("Smoothing");
|
||||||
|
|
||||||
|
|
|
@ -356,7 +356,7 @@ void menu_backlash();
|
||||||
#elif ENABLED(LIMITED_MAX_FR_EDITING)
|
#elif ENABLED(LIMITED_MAX_FR_EDITING)
|
||||||
DEFAULT_MAX_FEEDRATE
|
DEFAULT_MAX_FEEDRATE
|
||||||
#else
|
#else
|
||||||
LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999)
|
LOGICAL_AXIS_ARRAY(9999, 9999, 9999, 9999, 9999, 9999, 9999)
|
||||||
#endif
|
#endif
|
||||||
;
|
;
|
||||||
#if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES)
|
#if ENABLED(LIMITED_MAX_FR_EDITING) && !defined(MAX_FEEDRATE_EDIT_VALUES)
|
||||||
|
@ -399,7 +399,7 @@ void menu_backlash();
|
||||||
#elif ENABLED(LIMITED_MAX_ACCEL_EDITING)
|
#elif ENABLED(LIMITED_MAX_ACCEL_EDITING)
|
||||||
DEFAULT_MAX_ACCELERATION
|
DEFAULT_MAX_ACCELERATION
|
||||||
#else
|
#else
|
||||||
LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000)
|
LOGICAL_AXIS_ARRAY(99000, 99000, 99000, 99000, 99000, 99000, 99000)
|
||||||
#endif
|
#endif
|
||||||
;
|
;
|
||||||
#if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES)
|
#if ENABLED(LIMITED_MAX_ACCEL_EDITING) && !defined(MAX_ACCEL_EDIT_VALUES)
|
||||||
|
@ -477,7 +477,10 @@ void menu_backlash();
|
||||||
#else
|
#else
|
||||||
#define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c)
|
#define EDIT_JERK_C() EDIT_ITEM_FAST(float52sign, MSG_VC_JERK, &planner.max_jerk.c, 0.1f, max_jerk_edit.c)
|
||||||
#endif
|
#endif
|
||||||
LINEAR_AXIS_CODE(EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C());
|
LINEAR_AXIS_CODE(
|
||||||
|
EDIT_JERK(A), EDIT_JERK(B), EDIT_JERK_C(),
|
||||||
|
EDIT_JERK(I), EDIT_JERK(J), EDIT_JERK(K)
|
||||||
|
);
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e);
|
EDIT_ITEM_FAST(float52sign, MSG_VE_JERK, &planner.max_jerk.e, 0.1f, max_jerk_edit.e);
|
||||||
|
@ -515,7 +518,10 @@ void menu_advanced_steps_per_mm() {
|
||||||
BACK_ITEM(MSG_ADVANCED_SETTINGS);
|
BACK_ITEM(MSG_ADVANCED_SETTINGS);
|
||||||
|
|
||||||
#define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); })
|
#define EDIT_QSTEPS(Q) EDIT_ITEM_FAST(float51, MSG_##Q##_STEPS, &planner.settings.axis_steps_per_mm[_AXIS(Q)], 5, 9999, []{ planner.refresh_positioning(); })
|
||||||
LINEAR_AXIS_CODE(EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C));
|
LINEAR_AXIS_CODE(
|
||||||
|
EDIT_QSTEPS(A), EDIT_QSTEPS(B), EDIT_QSTEPS(C),
|
||||||
|
EDIT_QSTEPS(I), EDIT_QSTEPS(J), EDIT_QSTEPS(K)
|
||||||
|
);
|
||||||
|
|
||||||
#if ENABLED(DISTINCT_E_FACTORS)
|
#if ENABLED(DISTINCT_E_FACTORS)
|
||||||
LOOP_L_N(n, E_STEPPERS)
|
LOOP_L_N(n, E_STEPPERS)
|
||||||
|
|
|
@ -45,8 +45,21 @@ void menu_backlash() {
|
||||||
#endif
|
#endif
|
||||||
#define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f);
|
#define EDIT_BACKLASH_DISTANCE(N) EDIT_ITEM_FAST(float43, MSG_BACKLASH_##N, &backlash.distance_mm[_AXIS(N)], 0.0f, 9.9f);
|
||||||
if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A);
|
if (_CAN_CALI(A)) EDIT_BACKLASH_DISTANCE(A);
|
||||||
if (_CAN_CALI(B)) EDIT_BACKLASH_DISTANCE(B);
|
#if HAS_Y_AXIS && _CAN_CALI(B)
|
||||||
if (_CAN_CALI(C)) EDIT_BACKLASH_DISTANCE(C);
|
EDIT_BACKLASH_DISTANCE(B);
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS && _CAN_CALI(C)
|
||||||
|
EDIT_BACKLASH_DISTANCE(C);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 && _CAN_CALI(I)
|
||||||
|
EDIT_BACKLASH_DISTANCE(I);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && _CAN_CALI(J)
|
||||||
|
EDIT_BACKLASH_DISTANCE(J);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && _CAN_CALI(K)
|
||||||
|
EDIT_BACKLASH_DISTANCE(K);
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef BACKLASH_SMOOTHING_MM
|
#ifdef BACKLASH_SMOOTHING_MM
|
||||||
EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f);
|
EDIT_ITEM_FAST(float43, MSG_BACKLASH_SMOOTHING, &backlash.smoothing_mm, 0.0f, 9.9f);
|
||||||
|
|
|
@ -89,8 +89,21 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); }
|
void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); }
|
||||||
void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); }
|
#if HAS_Y_AXIS
|
||||||
void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); }
|
void lcd_move_y() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Y), Y_AXIS); }
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
void lcd_move_z() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_Z), Z_AXIS); }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
void lcd_move_i() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_I), I_AXIS); }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
void lcd_move_j() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_J), J_AXIS); }
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
void lcd_move_k() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_K), K_AXIS); }
|
||||||
|
#endif
|
||||||
|
|
||||||
#if E_MANUAL
|
#if E_MANUAL
|
||||||
|
|
||||||
|
@ -217,14 +230,27 @@ void menu_move() {
|
||||||
if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) {
|
if (NONE(IS_KINEMATIC, NO_MOTION_BEFORE_HOMING) || all_axes_homed()) {
|
||||||
if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) {
|
if (TERN1(DELTA, current_position.z <= delta_clip_start_height)) {
|
||||||
SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); });
|
SUBMENU(MSG_MOVE_X, []{ _menu_move_distance(X_AXIS, lcd_move_x); });
|
||||||
|
#if HAS_Y_AXIS
|
||||||
SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); });
|
SUBMENU(MSG_MOVE_Y, []{ _menu_move_distance(Y_AXIS, lcd_move_y); });
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
else
|
else
|
||||||
ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); });
|
ACTION_ITEM(MSG_FREE_XY, []{ line_to_z(delta_clip_start_height); ui.synchronize(); });
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); });
|
SUBMENU(MSG_MOVE_Z, []{ _menu_move_distance(Z_AXIS, lcd_move_z); });
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
SUBMENU(MSG_MOVE_I, []{ _menu_move_distance(I_AXIS, lcd_move_i); });
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
SUBMENU(MSG_MOVE_J, []{ _menu_move_distance(J_AXIS, lcd_move_j); });
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
SUBMENU(MSG_MOVE_K, []{ _menu_move_distance(K_AXIS, lcd_move_k); });
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
|
GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
|
||||||
|
@ -321,9 +347,22 @@ void menu_motion() {
|
||||||
GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
|
GCODES_ITEM(MSG_AUTO_HOME, G28_STR);
|
||||||
#if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU)
|
#if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU)
|
||||||
GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X"));
|
GCODES_ITEM(MSG_AUTO_HOME_X, PSTR("G28X"));
|
||||||
|
#if HAS_Y_AXIS
|
||||||
GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y"));
|
GCODES_ITEM(MSG_AUTO_HOME_Y, PSTR("G28Y"));
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z"));
|
GCODES_ITEM(MSG_AUTO_HOME_Z, PSTR("G28Z"));
|
||||||
#endif
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
GCODES_ITEM(MSG_AUTO_HOME_I, PSTR("G28" I_STR));
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
GCODES_ITEM(MSG_AUTO_HOME_J, PSTR("G28" J_STR));
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
GCODES_ITEM(MSG_AUTO_HOME_K, PSTR("G28" K_STR));
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Auto-calibration
|
// Auto-calibration
|
||||||
|
|
|
@ -95,54 +95,22 @@ void menu_tmc_current() {
|
||||||
void menu_tmc_hybrid_thrs() {
|
void menu_tmc_hybrid_thrs() {
|
||||||
START_MENU();
|
START_MENU();
|
||||||
BACK_ITEM(MSG_TMC_DRIVERS);
|
BACK_ITEM(MSG_TMC_DRIVERS);
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X, STR_X));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(X, STR_X);
|
TERN_(Y_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y));
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Y, STR_Y);
|
TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2));
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Z, STR_Z);
|
TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4));
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0));
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(X2, STR_X2);
|
TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2));
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Y2, STR_Y2);
|
TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5));
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7));
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Z2, STR_Z2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Z3, STR_Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(Z4, STR_Z4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E1, LCD_STR_E1);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E2, LCD_STR_E2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E3, LCD_STR_E3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E4, LCD_STR_E4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E5, LCD_STR_E5);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E6, LCD_STR_E6);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
TMC_EDIT_STORED_HYBRID_THRS(E7, LCD_STR_E7);
|
|
||||||
#endif
|
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -155,30 +123,17 @@ void menu_tmc_current() {
|
||||||
void menu_tmc_homing_thrs() {
|
void menu_tmc_homing_thrs() {
|
||||||
START_MENU();
|
START_MENU();
|
||||||
BACK_ITEM(MSG_TMC_DRIVERS);
|
BACK_ITEM(MSG_TMC_DRIVERS);
|
||||||
#if X_SENSORLESS
|
TERN_( X_SENSORLESS, TMC_EDIT_STORED_SGT(X));
|
||||||
TMC_EDIT_STORED_SGT(X);
|
TERN_(X2_SENSORLESS, TMC_EDIT_STORED_SGT(X2));
|
||||||
#if X2_SENSORLESS
|
TERN_( Y_SENSORLESS, TMC_EDIT_STORED_SGT(Y));
|
||||||
TMC_EDIT_STORED_SGT(X2);
|
TERN_(Y2_SENSORLESS, TMC_EDIT_STORED_SGT(Y2));
|
||||||
#endif
|
TERN_( Z_SENSORLESS, TMC_EDIT_STORED_SGT(Z));
|
||||||
#endif
|
TERN_(Z2_SENSORLESS, TMC_EDIT_STORED_SGT(Z2));
|
||||||
#if Y_SENSORLESS
|
TERN_(Z3_SENSORLESS, TMC_EDIT_STORED_SGT(Z3));
|
||||||
TMC_EDIT_STORED_SGT(Y);
|
TERN_(Z4_SENSORLESS, TMC_EDIT_STORED_SGT(Z4));
|
||||||
#if Y2_SENSORLESS
|
TERN_( I_SENSORLESS, TMC_EDIT_STORED_SGT(I));
|
||||||
TMC_EDIT_STORED_SGT(Y2);
|
TERN_( J_SENSORLESS, TMC_EDIT_STORED_SGT(J));
|
||||||
#endif
|
TERN_( K_SENSORLESS, TMC_EDIT_STORED_SGT(K));
|
||||||
#endif
|
|
||||||
#if Z_SENSORLESS
|
|
||||||
TMC_EDIT_STORED_SGT(Z);
|
|
||||||
#if Z2_SENSORLESS
|
|
||||||
TMC_EDIT_STORED_SGT(Z2);
|
|
||||||
#endif
|
|
||||||
#if Z3_SENSORLESS
|
|
||||||
TMC_EDIT_STORED_SGT(Z3);
|
|
||||||
#endif
|
|
||||||
#if Z4_SENSORLESS
|
|
||||||
TMC_EDIT_STORED_SGT(Z4);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -192,54 +147,22 @@ void menu_tmc_current() {
|
||||||
START_MENU();
|
START_MENU();
|
||||||
STATIC_ITEM(MSG_TMC_STEALTH_ENABLED);
|
STATIC_ITEM(MSG_TMC_STEALTH_ENABLED);
|
||||||
BACK_ITEM(MSG_TMC_DRIVERS);
|
BACK_ITEM(MSG_TMC_DRIVERS);
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_( X_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X, STR_X));
|
||||||
TMC_EDIT_STEP_MODE(X, STR_X);
|
TERN_(X2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(X2, STR_X2));
|
||||||
#endif
|
TERN_( Y_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y, STR_Y));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(Y2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Y2, STR_Y2));
|
||||||
TMC_EDIT_STEP_MODE(Y, STR_Y);
|
TERN_( Z_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z, STR_Z));
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z2, STR_Z2));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(Z3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z3, STR_Z3));
|
||||||
TMC_EDIT_STEP_MODE(Z, STR_Z);
|
TERN_(Z4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(Z4, STR_Z4));
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E0, LCD_STR_E0));
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(E1_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E1, LCD_STR_E1));
|
||||||
TMC_EDIT_STEP_MODE(X2, STR_X2);
|
TERN_(E2_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E2, LCD_STR_E2));
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E3, LCD_STR_E3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E4_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E4, LCD_STR_E4));
|
||||||
TMC_EDIT_STEP_MODE(Y2, STR_Y2);
|
TERN_(E5_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E5, LCD_STR_E5));
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E6, LCD_STR_E6));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E7_HAS_STEALTHCHOP, TMC_EDIT_STEP_MODE(E7, LCD_STR_E7));
|
||||||
TMC_EDIT_STEP_MODE(Z2, STR_Z2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
|
||||||
TMC_EDIT_STEP_MODE(Z3, STR_Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
TMC_EDIT_STEP_MODE(Z4, STR_Z4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
TMC_EDIT_STEP_MODE(E0, LCD_STR_E0);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
TMC_EDIT_STEP_MODE(E1, LCD_STR_E1);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
TMC_EDIT_STEP_MODE(E2, LCD_STR_E2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
TMC_EDIT_STEP_MODE(E3, LCD_STR_E3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
TMC_EDIT_STEP_MODE(E4, LCD_STR_E4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
TMC_EDIT_STEP_MODE(E5, LCD_STR_E5);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
TMC_EDIT_STEP_MODE(E6, LCD_STR_E6);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
TMC_EDIT_STEP_MODE(E7, LCD_STR_E7);
|
|
||||||
#endif
|
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -249,15 +172,9 @@ void menu_tmc() {
|
||||||
START_MENU();
|
START_MENU();
|
||||||
BACK_ITEM(MSG_ADVANCED_SETTINGS);
|
BACK_ITEM(MSG_ADVANCED_SETTINGS);
|
||||||
SUBMENU(MSG_TMC_CURRENT, menu_tmc_current);
|
SUBMENU(MSG_TMC_CURRENT, menu_tmc_current);
|
||||||
#if ENABLED(HYBRID_THRESHOLD)
|
TERN_(HYBRID_THRESHOLD, SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs));
|
||||||
SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs);
|
TERN_(SENSORLESS_HOMING, SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs));
|
||||||
#endif
|
TERN_(HAS_STEALTHCHOP, SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode));
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
|
||||||
SUBMENU(MSG_TMC_HOMING_THRS, menu_tmc_homing_thrs);
|
|
||||||
#endif
|
|
||||||
#if HAS_STEALTHCHOP
|
|
||||||
SUBMENU(MSG_TMC_STEPPING_MODE, menu_tmc_step_mode);
|
|
||||||
#endif
|
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -653,10 +653,12 @@ static void drawAxisValue(const AxisEnum axis) {
|
||||||
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
||||||
quick_feedback();
|
quick_feedback();
|
||||||
|
|
||||||
|
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||||
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
||||||
drawMessage("Too cold");
|
drawMessage("Too cold");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
const float diff = motionAxisState.currentStepSize * direction;
|
const float diff = motionAxisState.currentStepSize * direction;
|
||||||
|
|
||||||
|
|
|
@ -638,10 +638,12 @@ static void drawAxisValue(const AxisEnum axis) {
|
||||||
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
||||||
quick_feedback();
|
quick_feedback();
|
||||||
|
|
||||||
|
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||||
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
||||||
drawMessage("Too cold");
|
drawMessage("Too cold");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
const float diff = motionAxisState.currentStepSize * direction;
|
const float diff = motionAxisState.currentStepSize * direction;
|
||||||
|
|
||||||
|
|
|
@ -640,10 +640,12 @@ static void drawAxisValue(const AxisEnum axis) {
|
||||||
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
static void moveAxis(const AxisEnum axis, const int8_t direction) {
|
||||||
quick_feedback();
|
quick_feedback();
|
||||||
|
|
||||||
|
#if ENABLED(PREVENT_COLD_EXTRUSION)
|
||||||
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
if (axis == E_AXIS && thermalManager.tooColdToExtrude(motionAxisState.e_selection)) {
|
||||||
drawMessage("Too cold");
|
drawMessage("Too cold");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
const float diff = motionAxisState.currentStepSize * direction;
|
const float diff = motionAxisState.currentStepSize * direction;
|
||||||
|
|
||||||
|
|
|
@ -37,19 +37,27 @@ L64XX_Marlin L64xxManager;
|
||||||
#include "../../module/planner.h"
|
#include "../../module/planner.h"
|
||||||
#include "../../HAL/shared/Delay.h"
|
#include "../../HAL/shared/Delay.h"
|
||||||
|
|
||||||
static const char str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ",
|
static const char LINEAR_AXIS_LIST(
|
||||||
|
str_X[] PROGMEM = "X ", str_Y[] PROGMEM = "Y ", str_Z[] PROGMEM = "Z ",
|
||||||
|
str_I[] PROGMEM = AXIS4_STR " ", str_J[] PROGMEM = AXIS5_STR " ", str_K[] PROGMEM = AXIS6_STR " "
|
||||||
|
),
|
||||||
str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2",
|
str_X2[] PROGMEM = "X2", str_Y2[] PROGMEM = "Y2",
|
||||||
str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4",
|
str_Z2[] PROGMEM = "Z2", str_Z3[] PROGMEM = "Z3", str_Z4[] PROGMEM = "Z4",
|
||||||
|
LIST_N(EXTRUDERS,
|
||||||
str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1",
|
str_E0[] PROGMEM = "E0", str_E1[] PROGMEM = "E1",
|
||||||
str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3",
|
str_E2[] PROGMEM = "E2", str_E3[] PROGMEM = "E3",
|
||||||
str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5",
|
str_E4[] PROGMEM = "E4", str_E5[] PROGMEM = "E5",
|
||||||
str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7"
|
str_E6[] PROGMEM = "E6", str_E7[] PROGMEM = "E7"
|
||||||
|
)
|
||||||
;
|
;
|
||||||
|
|
||||||
|
#define _EN_ITEM(N) , str_E##N
|
||||||
PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = {
|
PGM_P const L64XX_Marlin::index_to_axis[] PROGMEM = {
|
||||||
str_X, str_Y, str_Z, str_X2, str_Y2, str_Z2, str_Z3, str_Z4,
|
LINEAR_AXIS_LIST(str_X, str_Y, str_Z, str_I, str_J, str_K),
|
||||||
str_E0, str_E1, str_E2, str_E3, str_E4, str_E5, str_E6, str_E7
|
str_X2, str_Y2, str_Z2, str_Z3, str_Z4
|
||||||
|
REPEAT(E_STEPPERS, _EN_ITEM)
|
||||||
};
|
};
|
||||||
|
#undef _EN_ITEM
|
||||||
|
|
||||||
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
|
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
|
||||||
#include "../../core/debug_out.h"
|
#include "../../core/debug_out.h"
|
||||||
|
@ -58,16 +66,17 @@ void echo_yes_no(const bool yes) { DEBUG_ECHOPGM_P(yes ? PSTR(" YES") : PSTR(" N
|
||||||
|
|
||||||
uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver
|
uint8_t L64XX_Marlin::dir_commands[MAX_L64XX]; // array to hold direction command for each driver
|
||||||
|
|
||||||
|
#define _EN_ITEM(N) , INVERT_E##N##_DIR
|
||||||
const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = {
|
const uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = {
|
||||||
INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR
|
LINEAR_AXIS_LIST(INVERT_X_DIR, INVERT_Y_DIR, INVERT_Z_DIR, INVERT_I_DIR, INVERT_J_DIR, INVERT_K_DIR)
|
||||||
, (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2
|
, (INVERT_X_DIR) ^ BOTH(X_DUAL_STEPPER_DRIVERS, INVERT_X2_VS_X_DIR) // X2
|
||||||
, (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2
|
, (INVERT_Y_DIR) ^ BOTH(Y_DUAL_STEPPER_DRIVERS, INVERT_Y2_VS_Y_DIR) // Y2
|
||||||
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2
|
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z2_VS_Z_DIR) // Z2
|
||||||
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3
|
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z3_VS_Z_DIR) // Z3
|
||||||
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4
|
, (INVERT_Z_DIR) ^ ENABLED(INVERT_Z4_VS_Z_DIR) // Z4
|
||||||
, INVERT_E0_DIR, INVERT_E1_DIR, INVERT_E2_DIR, INVERT_E3_DIR
|
REPEAT(E_STEPPERS, _EN_ITEM)
|
||||||
, INVERT_E4_DIR, INVERT_E5_DIR, INVERT_E6_DIR, INVERT_E7_DIR
|
|
||||||
};
|
};
|
||||||
|
#undef _EN_ITEM
|
||||||
|
|
||||||
volatile uint8_t L64XX_Marlin::spi_abort = false;
|
volatile uint8_t L64XX_Marlin::spi_abort = false;
|
||||||
uint8_t L64XX_Marlin::spi_active = false;
|
uint8_t L64XX_Marlin::spi_active = false;
|
||||||
|
@ -326,6 +335,15 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
|
||||||
#if AXIS_IS_L64XX(Z)
|
#if AXIS_IS_L64XX(Z)
|
||||||
case Z : SET_L6470_PARAM(Z); break;
|
case Z : SET_L6470_PARAM(Z); break;
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
case I : SET_L6470_PARAM(I); break;
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
case J : SET_L6470_PARAM(J); break;
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
case K : SET_L6470_PARAM(K); break;
|
||||||
|
#endif
|
||||||
#if AXIS_IS_L64XX(X2)
|
#if AXIS_IS_L64XX(X2)
|
||||||
case X2: SET_L6470_PARAM(X2); break;
|
case X2: SET_L6470_PARAM(X2); break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -370,8 +388,7 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
|
||||||
|
|
||||||
inline void echo_min_max(const char a, const_float_t min, const_float_t max) {
|
inline void echo_min_max(const char a, const_float_t min, const_float_t max) {
|
||||||
DEBUG_CHAR(' '); DEBUG_CHAR(a);
|
DEBUG_CHAR(' '); DEBUG_CHAR(a);
|
||||||
DEBUG_ECHOPAIR(" min = ", min);
|
DEBUG_ECHOLNPAIR(" min = ", min, " max = ", max);
|
||||||
DEBUG_ECHOLNPAIR(" max = ", max);
|
|
||||||
}
|
}
|
||||||
inline void echo_oct_used(const_float_t oct, const uint8_t stall) {
|
inline void echo_oct_used(const_float_t oct, const uint8_t stall) {
|
||||||
DEBUG_ECHOPAIR("over_current_threshold used : ", oct);
|
DEBUG_ECHOPAIR("over_current_threshold used : ", oct);
|
||||||
|
@ -433,10 +450,15 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
|
||||||
// Position calcs & checks
|
// Position calcs & checks
|
||||||
//
|
//
|
||||||
|
|
||||||
const float X_center = LOGICAL_X_POSITION(current_position.x),
|
const float LOGICAL_AXIS_LIST(
|
||||||
|
E_center = current_position.e,
|
||||||
|
X_center = LOGICAL_X_POSITION(current_position.x),
|
||||||
Y_center = LOGICAL_Y_POSITION(current_position.y),
|
Y_center = LOGICAL_Y_POSITION(current_position.y),
|
||||||
Z_center = LOGICAL_Z_POSITION(current_position.z),
|
Z_center = LOGICAL_Z_POSITION(current_position.z),
|
||||||
E_center = current_position.e;
|
I_center = LOGICAL_I_POSITION(current_position.i),
|
||||||
|
J_center = LOGICAL_J_POSITION(current_position.j),
|
||||||
|
K_center = LOGICAL_K_POSITION(current_position.k)
|
||||||
|
);
|
||||||
|
|
||||||
switch (axis_mon[0][0]) {
|
switch (axis_mon[0][0]) {
|
||||||
default: position_max = position_min = 0; break;
|
default: position_max = position_min = 0; break;
|
||||||
|
@ -451,6 +473,7 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
|
||||||
}
|
}
|
||||||
} break;
|
} break;
|
||||||
|
|
||||||
|
#if HAS_Y_AXIS
|
||||||
case 'Y': {
|
case 'Y': {
|
||||||
position_min = Y_center - displacement;
|
position_min = Y_center - displacement;
|
||||||
position_max = Y_center + displacement;
|
position_max = Y_center + displacement;
|
||||||
|
@ -460,7 +483,9 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
} break;
|
} break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
case 'Z': {
|
case 'Z': {
|
||||||
position_min = Z_center - displacement;
|
position_min = Z_center - displacement;
|
||||||
position_max = Z_center + displacement;
|
position_max = Z_center + displacement;
|
||||||
|
@ -470,12 +495,51 @@ uint8_t L64XX_Marlin::get_user_input(uint8_t &driver_count, L64XX_axis_t axis_in
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
} break;
|
} break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
case AXIS4_NAME: {
|
||||||
|
position_min = I_center - displacement;
|
||||||
|
position_max = I_center + displacement;
|
||||||
|
echo_min_max(AXIS4_NAME, position_min, position_max);
|
||||||
|
if (TERN0(HAS_ENDSTOPS, position_min < (I_MIN_POS) || position_max > (I_MAX_POS))) {
|
||||||
|
err_out_of_bounds();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
case AXIS5_NAME: {
|
||||||
|
position_min = J_center - displacement;
|
||||||
|
position_max = J_center + displacement;
|
||||||
|
echo_min_max(AXIS5_NAME, position_min, position_max);
|
||||||
|
if (TERN1(HAS_ENDSTOPS, position_min < (J_MIN_POS) || position_max > (J_MAX_POS))) {
|
||||||
|
err_out_of_bounds();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
case AXIS6_NAME: {
|
||||||
|
position_min = K_center - displacement;
|
||||||
|
position_max = K_center + displacement;
|
||||||
|
echo_min_max(AXIS6_NAME, position_min, position_max);
|
||||||
|
if (TERN2(HAS_ENDSTOPS, position_min < (K_MIN_POS) || position_max > (K_MAX_POS))) {
|
||||||
|
err_out_of_bounds();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
} break;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_EXTRUDERS
|
||||||
case 'E': {
|
case 'E': {
|
||||||
position_min = E_center - displacement;
|
position_min = E_center - displacement;
|
||||||
position_max = E_center + displacement;
|
position_max = E_center + displacement;
|
||||||
echo_min_max('E', position_min, position_max);
|
echo_min_max('E', position_min, position_max);
|
||||||
} break;
|
} break;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -660,7 +724,7 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
|
||||||
bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc.
|
bool L64XX_Marlin::monitor_paused = false; // Flag to skip monitor during M122, M906, M916, M917, M918, etc.
|
||||||
|
|
||||||
struct L6470_driver_data {
|
struct L6470_driver_data {
|
||||||
uint8_t driver_index;
|
L64XX_axis_t driver_index;
|
||||||
uint32_t driver_status;
|
uint32_t driver_status;
|
||||||
uint8_t is_otw;
|
uint8_t is_otw;
|
||||||
uint8_t otw_counter;
|
uint8_t otw_counter;
|
||||||
|
@ -671,52 +735,61 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
|
||||||
|
|
||||||
L6470_driver_data driver_L6470_data[] = {
|
L6470_driver_data driver_L6470_data[] = {
|
||||||
#if AXIS_IS_L64XX(X)
|
#if AXIS_IS_L64XX(X)
|
||||||
{ 0, 0, 0, 0, 0, 0, 0 },
|
{ X, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Y)
|
#if AXIS_IS_L64XX(Y)
|
||||||
{ 1, 0, 0, 0, 0, 0, 0 },
|
{ Y, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Z)
|
#if AXIS_IS_L64XX(Z)
|
||||||
{ 2, 0, 0, 0, 0, 0, 0 },
|
{ Z, 0, 0, 0, 0, 0, 0 },
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
{ I, 0, 0, 0, 0, 0, 0 },
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
{ J, 0, 0, 0, 0, 0, 0 },
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
{ K, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(X2)
|
#if AXIS_IS_L64XX(X2)
|
||||||
{ 3, 0, 0, 0, 0, 0, 0 },
|
{ X2, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Y2)
|
#if AXIS_IS_L64XX(Y2)
|
||||||
{ 4, 0, 0, 0, 0, 0, 0 },
|
{ Y2, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Z2)
|
#if AXIS_IS_L64XX(Z2)
|
||||||
{ 5, 0, 0, 0, 0, 0, 0 },
|
{ Z2, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Z3)
|
#if AXIS_IS_L64XX(Z3)
|
||||||
{ 6, 0, 0, 0, 0, 0, 0 },
|
{ Z3, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(Z4)
|
#if AXIS_IS_L64XX(Z4)
|
||||||
{ 7, 0, 0, 0, 0, 0, 0 },
|
{ Z4, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
{ 8, 0, 0, 0, 0, 0, 0 },
|
{ E0, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E1)
|
#if AXIS_IS_L64XX(E1)
|
||||||
{ 9, 0, 0, 0, 0, 0, 0 },
|
{ E1, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E2)
|
#if AXIS_IS_L64XX(E2)
|
||||||
{ 10, 0, 0, 0, 0, 0, 0 },
|
{ E2, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E3)
|
#if AXIS_IS_L64XX(E3)
|
||||||
{ 11, 0, 0, 0, 0, 0, 0 },
|
{ E3, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E4)
|
#if AXIS_IS_L64XX(E4)
|
||||||
{ 12, 0, 0, 0, 0, 0, 0 },
|
{ E4, 0, 0, 0, 0, 0, 0 },
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E5)
|
#if AXIS_IS_L64XX(E5)
|
||||||
{ 13, 0, 0, 0, 0, 0, 0 }
|
{ E5, 0, 0, 0, 0, 0, 0 }
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E6)
|
#if AXIS_IS_L64XX(E6)
|
||||||
{ 14, 0, 0, 0, 0, 0, 0 }
|
{ E6, 0, 0, 0, 0, 0, 0 }
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_IS_L64XX(E7)
|
#if AXIS_IS_L64XX(E7)
|
||||||
{ 16, 0, 0, 0, 0, 0, 0 }
|
{ E7, 0, 0, 0, 0, 0, 0 }
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -863,6 +936,15 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
|
||||||
#if AXIS_IS_L64XX(Z)
|
#if AXIS_IS_L64XX(Z)
|
||||||
monitor_update(Z);
|
monitor_update(Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
monitor_update(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
monitor_update(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
monitor_update(K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_L64XX(X2)
|
#if AXIS_IS_L64XX(X2)
|
||||||
monitor_update(X2);
|
monitor_update(X2);
|
||||||
#endif
|
#endif
|
||||||
|
@ -896,6 +978,12 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
|
||||||
#if AXIS_IS_L64XX(E5)
|
#if AXIS_IS_L64XX(E5)
|
||||||
monitor_update(E5);
|
monitor_update(E5);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(E6)
|
||||||
|
monitor_update(E6);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(E7)
|
||||||
|
monitor_update(E7);
|
||||||
|
#endif
|
||||||
|
|
||||||
if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL();
|
if (TERN0(L6470_DEBUG, report_L6470_status)) DEBUG_EOL();
|
||||||
|
|
||||||
|
|
|
@ -35,7 +35,9 @@
|
||||||
#define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
|
#define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
|
||||||
#define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7))
|
#define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5) || AXIS_IS_L64XX(E6) || AXIS_IS_L64XX(E7))
|
||||||
|
|
||||||
enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, MAX_L64XX };
|
#define _EN_ITEM(N) , E##N
|
||||||
|
enum L64XX_axis_t : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM), MAX_L64XX };
|
||||||
|
#undef _EN_ITEM
|
||||||
|
|
||||||
class L64XX_Marlin : public L64XXHelper {
|
class L64XX_Marlin : public L64XXHelper {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -52,10 +52,9 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) {
|
vector_3 vector_3::cross(const vector_3 &left, const vector_3 &right) {
|
||||||
const xyz_float_t &lv = left, &rv = right;
|
return vector_3(left.y * right.z - left.z * right.y, // YZ cross
|
||||||
return vector_3(lv.y * rv.z - lv.z * rv.y, // YZ cross
|
left.z * right.x - left.x * right.z, // ZX cross
|
||||||
lv.z * rv.x - lv.x * rv.z, // ZX cross
|
left.x * right.y - left.y * right.x); // XY cross
|
||||||
lv.x * rv.y - lv.y * rv.x); // XY cross
|
|
||||||
}
|
}
|
||||||
|
|
||||||
vector_3 vector_3::get_normal() const {
|
vector_3 vector_3::get_normal() const {
|
||||||
|
@ -64,16 +63,16 @@ vector_3 vector_3::get_normal() const {
|
||||||
return normalized;
|
return normalized;
|
||||||
}
|
}
|
||||||
|
|
||||||
void vector_3::normalize() {
|
float vector_3::magnitude() const { return SQRT(sq(x) + sq(y) + sq(z)); }
|
||||||
*this *= RSQRT(sq(x) + sq(y) + sq(z));
|
|
||||||
}
|
void vector_3::normalize() { *this *= RSQRT(sq(x) + sq(y) + sq(z)); }
|
||||||
|
|
||||||
// Apply a rotation to the matrix
|
// Apply a rotation to the matrix
|
||||||
void vector_3::apply_rotation(const matrix_3x3 &matrix) {
|
void vector_3::apply_rotation(const matrix_3x3 &matrix) {
|
||||||
const float _x = x, _y = y, _z = z;
|
const float _x = x, _y = y, _z = z;
|
||||||
*this = { matrix.vectors[0][0] * _x + matrix.vectors[1][0] * _y + matrix.vectors[2][0] * _z,
|
*this = { matrix.vectors[0].x * _x + matrix.vectors[1].x * _y + matrix.vectors[2].x * _z,
|
||||||
matrix.vectors[0][1] * _x + matrix.vectors[1][1] * _y + matrix.vectors[2][1] * _z,
|
matrix.vectors[0].y * _x + matrix.vectors[1].y * _y + matrix.vectors[2].y * _z,
|
||||||
matrix.vectors[0][2] * _x + matrix.vectors[1][2] * _y + matrix.vectors[2][2] * _z };
|
matrix.vectors[0].z * _x + matrix.vectors[1].z * _y + matrix.vectors[2].z * _z };
|
||||||
}
|
}
|
||||||
|
|
||||||
void vector_3::debug(PGM_P const title) {
|
void vector_3::debug(PGM_P const title) {
|
||||||
|
@ -105,9 +104,9 @@ matrix_3x3 matrix_3x3::create_from_rows(const vector_3 &row_0, const vector_3 &r
|
||||||
//row_1.debug(PSTR("row_1"));
|
//row_1.debug(PSTR("row_1"));
|
||||||
//row_2.debug(PSTR("row_2"));
|
//row_2.debug(PSTR("row_2"));
|
||||||
matrix_3x3 new_matrix;
|
matrix_3x3 new_matrix;
|
||||||
new_matrix.vectors[0] = row_0;
|
new_matrix.vectors[0].x = row_0.x; new_matrix.vectors[1].y = row_0.y; new_matrix.vectors[2].z = row_0.z;
|
||||||
new_matrix.vectors[1] = row_1;
|
new_matrix.vectors[3].x = row_1.x; new_matrix.vectors[4].y = row_1.y; new_matrix.vectors[5].z = row_1.z;
|
||||||
new_matrix.vectors[2] = row_2;
|
new_matrix.vectors[6].x = row_2.x; new_matrix.vectors[7].y = row_2.y; new_matrix.vectors[8].z = row_2.z;
|
||||||
//new_matrix.debug(PSTR("new_matrix"));
|
//new_matrix.debug(PSTR("new_matrix"));
|
||||||
return new_matrix;
|
return new_matrix;
|
||||||
}
|
}
|
||||||
|
|
|
@ -44,12 +44,16 @@
|
||||||
|
|
||||||
class matrix_3x3;
|
class matrix_3x3;
|
||||||
|
|
||||||
struct vector_3 : xyz_float_t {
|
struct vector_3 {
|
||||||
vector_3(const_float_t _x, const_float_t _y, const_float_t _z) { set(_x, _y, _z); }
|
union {
|
||||||
vector_3(const xy_float_t &in) { set(in.x, in.y); }
|
struct { float x, y, z; };
|
||||||
vector_3(const xyz_float_t &in) { set(in.x, in.y, in.z); }
|
float pos[3];
|
||||||
vector_3(const xyze_float_t &in) { set(in.x, in.y, in.z); }
|
};
|
||||||
vector_3() { reset(); }
|
vector_3(const_float_t _x, const_float_t _y, const_float_t _z) : x(_x), y(_y), z(_z) {}
|
||||||
|
vector_3(const xy_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); }
|
||||||
|
vector_3(const xyz_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); }
|
||||||
|
vector_3(const xyze_float_t &in) { x = in.x; TERN_(HAS_Y_AXIS, y = in.y); TERN_(HAS_Z_AXIS, z = in.z); }
|
||||||
|
vector_3() { x = y = z = 0; }
|
||||||
|
|
||||||
// Factory method
|
// Factory method
|
||||||
static vector_3 cross(const vector_3 &a, const vector_3 &b);
|
static vector_3 cross(const vector_3 &a, const vector_3 &b);
|
||||||
|
@ -59,19 +63,26 @@ struct vector_3 : xyz_float_t {
|
||||||
void apply_rotation(const matrix_3x3 &matrix);
|
void apply_rotation(const matrix_3x3 &matrix);
|
||||||
|
|
||||||
// Accessors
|
// Accessors
|
||||||
float get_length() const;
|
float magnitude() const;
|
||||||
vector_3 get_normal() const;
|
vector_3 get_normal() const;
|
||||||
|
|
||||||
// Operators
|
// Operators
|
||||||
FORCE_INLINE vector_3 operator+(const vector_3 &v) const { vector_3 o = *this; o += v; return o; }
|
float& operator[](const int n) { return pos[n]; }
|
||||||
FORCE_INLINE vector_3 operator-(const vector_3 &v) const { vector_3 o = *this; o -= v; return o; }
|
const float& operator[](const int n) const { return pos[n]; }
|
||||||
FORCE_INLINE vector_3 operator*(const float &v) const { vector_3 o = *this; o *= v; return o; }
|
|
||||||
|
vector_3& operator*=(const float &v) { x *= v; y *= v; z *= v; return *this; }
|
||||||
|
vector_3 operator+(const vector_3 &v) { return vector_3(x + v.x, y + v.y, z + v.z); }
|
||||||
|
vector_3 operator-(const vector_3 &v) { return vector_3(x - v.x, y - v.y, z - v.z); }
|
||||||
|
vector_3 operator*(const float &v) { return vector_3(x * v, y * v, z * v); }
|
||||||
|
|
||||||
|
operator xy_float_t() { return xy_float_t({ x, y }); }
|
||||||
|
operator xyz_float_t() { return xyz_float_t({ x, y, z }); }
|
||||||
|
|
||||||
void debug(PGM_P const title);
|
void debug(PGM_P const title);
|
||||||
};
|
};
|
||||||
|
|
||||||
struct matrix_3x3 {
|
struct matrix_3x3 {
|
||||||
abc_float_t vectors[3];
|
vector_3 vectors[3];
|
||||||
|
|
||||||
// Factory methods
|
// Factory methods
|
||||||
static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2);
|
static matrix_3x3 create_from_rows(const vector_3 &row_0, const vector_3 &row_1, const vector_3 &row_2);
|
||||||
|
@ -83,6 +94,4 @@ struct matrix_3x3 {
|
||||||
void debug(PGM_P const title);
|
void debug(PGM_P const title);
|
||||||
|
|
||||||
void apply_rotation_xyz(float &x, float &y, float &z);
|
void apply_rotation_xyz(float &x, float &y, float &z);
|
||||||
|
|
||||||
FORCE_INLINE void apply_rotation_xyz(xyz_pos_t &pos) { apply_rotation_xyz(pos.x, pos.y, pos.z); }
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -245,6 +245,9 @@ void home_delta() {
|
||||||
TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS));
|
TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS));
|
||||||
TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS));
|
TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS));
|
||||||
TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS));
|
TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS));
|
||||||
|
TERN_(I_SENSORLESS, sensorless_t stealth_states_i = start_sensorless_homing_per_axis(I_AXIS));
|
||||||
|
TERN_(J_SENSORLESS, sensorless_t stealth_states_j = start_sensorless_homing_per_axis(J_AXIS));
|
||||||
|
TERN_(K_SENSORLESS, sensorless_t stealth_states_k = start_sensorless_homing_per_axis(K_AXIS));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Move all carriages together linearly until an endstop is hit.
|
// Move all carriages together linearly until an endstop is hit.
|
||||||
|
@ -257,6 +260,9 @@ void home_delta() {
|
||||||
TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x));
|
TERN_(X_SENSORLESS, end_sensorless_homing_per_axis(X_AXIS, stealth_states_x));
|
||||||
TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y));
|
TERN_(Y_SENSORLESS, end_sensorless_homing_per_axis(Y_AXIS, stealth_states_y));
|
||||||
TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z));
|
TERN_(Z_SENSORLESS, end_sensorless_homing_per_axis(Z_AXIS, stealth_states_z));
|
||||||
|
TERN_(I_SENSORLESS, end_sensorless_homing_per_axis(I_AXIS, stealth_states_i));
|
||||||
|
TERN_(J_SENSORLESS, end_sensorless_homing_per_axis(J_AXIS, stealth_states_j));
|
||||||
|
TERN_(K_SENSORLESS, end_sensorless_homing_per_axis(K_AXIS, stealth_states_k));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
endstops.validate_homing_move();
|
endstops.validate_homing_move();
|
||||||
|
|
|
@ -259,6 +259,66 @@ void Endstops::init() {
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_I_MIN
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_IMIN)
|
||||||
|
SET_INPUT_PULLUP(I_MIN_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_IMIN)
|
||||||
|
SET_INPUT_PULLDOWN(I_MIN_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(I_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_I_MAX
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_IMAX)
|
||||||
|
SET_INPUT_PULLUP(I_MAX_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_IMAX)
|
||||||
|
SET_INPUT_PULLDOWN(I_MAX_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(I_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_MIN
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_JMIN)
|
||||||
|
SET_INPUT_PULLUP(J_MIN_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_IMIN)
|
||||||
|
SET_INPUT_PULLDOWN(J_MIN_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(J_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_MAX
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_JMAX)
|
||||||
|
SET_INPUT_PULLUP(J_MAX_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_JMAX)
|
||||||
|
SET_INPUT_PULLDOWN(J_MAX_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(J_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_MIN
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_KMIN)
|
||||||
|
SET_INPUT_PULLUP(K_MIN_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_KMIN)
|
||||||
|
SET_INPUT_PULLDOWN(K_MIN_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(K_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_MAX
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_KMAX)
|
||||||
|
SET_INPUT_PULLUP(K_MAX_PIN);
|
||||||
|
#elif ENABLED(ENDSTOPPULLDOWN_KMIN)
|
||||||
|
SET_INPUT_PULLDOWN(K_MAX_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(K_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if PIN_EXISTS(CALIBRATION)
|
#if PIN_EXISTS(CALIBRATION)
|
||||||
#if ENABLED(CALIBRATION_PIN_PULLUP)
|
#if ENABLED(CALIBRATION_PIN_PULLUP)
|
||||||
SET_INPUT_PULLUP(CALIBRATION_PIN);
|
SET_INPUT_PULLUP(CALIBRATION_PIN);
|
||||||
|
@ -361,7 +421,7 @@ void Endstops::event_handler() {
|
||||||
prev_hit_state = hit_state;
|
prev_hit_state = hit_state;
|
||||||
if (hit_state) {
|
if (hit_state) {
|
||||||
#if HAS_STATUS_MESSAGE
|
#if HAS_STATUS_MESSAGE
|
||||||
char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' '),
|
char LINEAR_AXIS_LIST(chrX = ' ', chrY = ' ', chrZ = ' ', chrI = ' ', chrJ = ' ', chrK = ' '),
|
||||||
chrP = ' ';
|
chrP = ' ';
|
||||||
#define _SET_STOP_CHAR(A,C) (chr## A = C)
|
#define _SET_STOP_CHAR(A,C) (chr## A = C)
|
||||||
#else
|
#else
|
||||||
|
@ -378,12 +438,20 @@ void Endstops::event_handler() {
|
||||||
#define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X')
|
#define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X')
|
||||||
#define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y')
|
#define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y')
|
||||||
#define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z')
|
#define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z')
|
||||||
|
#define ENDSTOP_HIT_TEST_I() _ENDSTOP_HIT_TEST(I,'I')
|
||||||
|
#define ENDSTOP_HIT_TEST_J() _ENDSTOP_HIT_TEST(J,'J')
|
||||||
|
#define ENDSTOP_HIT_TEST_K() _ENDSTOP_HIT_TEST(K,'K')
|
||||||
|
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOPGM(STR_ENDSTOPS_HIT);
|
SERIAL_ECHOPGM(STR_ENDSTOPS_HIT);
|
||||||
ENDSTOP_HIT_TEST_X();
|
LINEAR_AXIS_CODE(
|
||||||
ENDSTOP_HIT_TEST_Y();
|
ENDSTOP_HIT_TEST_X(),
|
||||||
ENDSTOP_HIT_TEST_Z();
|
ENDSTOP_HIT_TEST_Y(),
|
||||||
|
ENDSTOP_HIT_TEST_Z(),
|
||||||
|
_ENDSTOP_HIT_TEST(I,'I'),
|
||||||
|
_ENDSTOP_HIT_TEST(J,'J'),
|
||||||
|
_ENDSTOP_HIT_TEST(K,'K')
|
||||||
|
);
|
||||||
|
|
||||||
#if HAS_CUSTOM_PROBE_PIN
|
#if HAS_CUSTOM_PROBE_PIN
|
||||||
#define P_AXIS Z_AXIS
|
#define P_AXIS Z_AXIS
|
||||||
|
@ -395,7 +463,7 @@ void Endstops::event_handler() {
|
||||||
ui.status_printf_P(0,
|
ui.status_printf_P(0,
|
||||||
PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"),
|
PSTR(S_FMT GANG_N_1(LINEAR_AXES, " %c") " %c"),
|
||||||
GET_TEXT(MSG_LCD_ENDSTOPS),
|
GET_TEXT(MSG_LCD_ENDSTOPS),
|
||||||
LINEAR_AXIS_LIST(chrX, chrY, chrZ), chrP
|
LINEAR_AXIS_LIST(chrX, chrY, chrZ, chrI, chrJ, chrK), chrP
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
|
@ -477,6 +545,24 @@ void _O2 Endstops::report_states() {
|
||||||
#if HAS_Z4_MAX
|
#if HAS_Z4_MAX
|
||||||
ES_REPORT(Z4_MAX);
|
ES_REPORT(Z4_MAX);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MIN
|
||||||
|
ES_REPORT(I_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_I_MAX
|
||||||
|
ES_REPORT(I_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MIN
|
||||||
|
ES_REPORT(J_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
ES_REPORT(J_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MIN
|
||||||
|
ES_REPORT(K_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
ES_REPORT(K_MAX);
|
||||||
|
#endif
|
||||||
#if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH)
|
#if BOTH(MARLIN_DEV_MODE, PROBE_ACTIVATION_SWITCH)
|
||||||
print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN));
|
print_es_state(probe_switch_activated(), PSTR(STR_PROBE_EN));
|
||||||
#endif
|
#endif
|
||||||
|
@ -549,6 +635,10 @@ void Endstops::update() {
|
||||||
#define Z_AXIS_HEAD Z_AXIS
|
#define Z_AXIS_HEAD Z_AXIS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define I_AXIS_HEAD I_AXIS
|
||||||
|
#define J_AXIS_HEAD J_AXIS
|
||||||
|
#define K_AXIS_HEAD K_AXIS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Check and update endstops
|
* Check and update endstops
|
||||||
*/
|
*/
|
||||||
|
@ -656,6 +746,84 @@ void Endstops::update() {
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_I_MIN
|
||||||
|
#if ENABLED(I_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(I, MIN);
|
||||||
|
#if HAS_I2_MIN
|
||||||
|
UPDATE_ENDSTOP_BIT(I2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(I_MIN, I2_MIN);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(I, MIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_I_MAX
|
||||||
|
#if ENABLED(I_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(I, MAX);
|
||||||
|
#if HAS_I2_MAX
|
||||||
|
UPDATE_ENDSTOP_BIT(I2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(I_MAX, I2_MAX);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(I, MAX);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_MIN
|
||||||
|
#if ENABLED(J_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(J, MIN);
|
||||||
|
#if HAS_J2_MIN
|
||||||
|
UPDATE_ENDSTOP_BIT(J2, MIN);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(J_MIN, J2_MIN);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(J, MIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_MAX
|
||||||
|
#if ENABLED(J_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(J, MAX);
|
||||||
|
#if HAS_J2_MAX
|
||||||
|
UPDATE_ENDSTOP_BIT(J2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(J_MAX, J2_MAX);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(J, MAX);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_MIN
|
||||||
|
#if ENABLED(K_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(K, MIN);
|
||||||
|
#if HAS_K2_MIN
|
||||||
|
UPDATE_ENDSTOP_BIT(K2, MIN);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(K_MIN, K2_MIN);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(K, MIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_MAX
|
||||||
|
#if ENABLED(K_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(K, MAX);
|
||||||
|
#if HAS_K2_MAX
|
||||||
|
UPDATE_ENDSTOP_BIT(K2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_LIVE_STATE(K_MAX, K2_MAX);
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
UPDATE_ENDSTOP_BIT(K, MAX);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENDSTOP_NOISE_THRESHOLD
|
#if ENDSTOP_NOISE_THRESHOLD
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -804,6 +972,7 @@ void Endstops::update() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAS_Y_AXIS
|
||||||
if (stepper.axis_is_moving(Y_AXIS)) {
|
if (stepper.axis_is_moving(Y_AXIS)) {
|
||||||
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
|
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
|
||||||
#if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN)
|
#if HAS_Y_MIN || (Y_SPI_SENSORLESS && Y_HOME_TO_MIN)
|
||||||
|
@ -834,7 +1003,9 @@ void Endstops::update() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
if (stepper.axis_is_moving(Z_AXIS)) {
|
if (stepper.axis_is_moving(Z_AXIS)) {
|
||||||
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
|
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
|
||||||
|
|
||||||
|
@ -877,6 +1048,52 @@ void Endstops::update() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
if (stepper.axis_is_moving(I_AXIS)) {
|
||||||
|
if (stepper.motor_direction(I_AXIS_HEAD)) { // -direction
|
||||||
|
#if HAS_I_MIN || (I_SPI_SENSORLESS && I_HOME_TO_MIN)
|
||||||
|
PROCESS_ENDSTOP(I, MIN);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else { // +direction
|
||||||
|
#if HAS_I_MAX || (I_SPI_SENSORLESS && I_HOME_TO_MAX)
|
||||||
|
PROCESS_ENDSTOP(I, MAX);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
if (stepper.axis_is_moving(J_AXIS)) {
|
||||||
|
if (stepper.motor_direction(J_AXIS_HEAD)) { // -direction
|
||||||
|
#if HAS_J_MIN || (J_SPI_SENSORLESS && J_HOME_TO_MIN)
|
||||||
|
PROCESS_ENDSTOP(J, MIN);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else { // +direction
|
||||||
|
#if HAS_J_MAX || (J_SPI_SENSORLESS && J_HOME_TO_MAX)
|
||||||
|
PROCESS_ENDSTOP(J, MAX);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
if (stepper.axis_is_moving(K_AXIS)) {
|
||||||
|
if (stepper.motor_direction(K_AXIS_HEAD)) { // -direction
|
||||||
|
#if HAS_K_MIN || (K_SPI_SENSORLESS && K_HOME_TO_MIN)
|
||||||
|
PROCESS_ENDSTOP(K, MIN);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else { // +direction
|
||||||
|
#if HAS_K_MAX || (K_SPI_SENSORLESS && K_HOME_TO_MAX)
|
||||||
|
PROCESS_ENDSTOP(K, MAX);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
} // Endstops::update()
|
} // Endstops::update()
|
||||||
|
|
||||||
#if ENABLED(SPI_ENDSTOPS)
|
#if ENABLED(SPI_ENDSTOPS)
|
||||||
|
@ -919,6 +1136,24 @@ void Endstops::update() {
|
||||||
hit = true;
|
hit = true;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#if I_SPI_SENSORLESS
|
||||||
|
if (tmc_spi_homing.i && stepperI.test_stall_status()) {
|
||||||
|
SBI(live_state, I_ENDSTOP);
|
||||||
|
hit = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if J_SPI_SENSORLESS
|
||||||
|
if (tmc_spi_homing.j && stepperJ.test_stall_status()) {
|
||||||
|
SBI(live_state, J_ENDSTOP);
|
||||||
|
hit = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if K_SPI_SENSORLESS
|
||||||
|
if (tmc_spi_homing.k && stepperK.test_stall_status()) {
|
||||||
|
SBI(live_state, K_ENDSTOP);
|
||||||
|
hit = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update();
|
if (TERN0(ENDSTOP_INTERRUPTS_FEATURE, hit)) update();
|
||||||
|
|
||||||
|
@ -929,6 +1164,9 @@ void Endstops::update() {
|
||||||
TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP));
|
TERN_(X_SPI_SENSORLESS, CBI(live_state, X_ENDSTOP));
|
||||||
TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP));
|
TERN_(Y_SPI_SENSORLESS, CBI(live_state, Y_ENDSTOP));
|
||||||
TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP));
|
TERN_(Z_SPI_SENSORLESS, CBI(live_state, Z_ENDSTOP));
|
||||||
|
TERN_(I_SPI_SENSORLESS, CBI(live_state, I_ENDSTOP));
|
||||||
|
TERN_(J_SPI_SENSORLESS, CBI(live_state, J_ENDSTOP));
|
||||||
|
TERN_(K_SPI_SENSORLESS, CBI(live_state, K_ENDSTOP));
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // SPI_ENDSTOPS
|
#endif // SPI_ENDSTOPS
|
||||||
|
@ -1005,6 +1243,24 @@ void Endstops::update() {
|
||||||
#if HAS_Z4_MAX
|
#if HAS_Z4_MAX
|
||||||
ES_GET_STATE(Z4_MAX);
|
ES_GET_STATE(Z4_MAX);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MAX
|
||||||
|
ES_GET_STATE(I_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_I_MIN
|
||||||
|
ES_GET_STATE(I_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
ES_GET_STATE(J_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MIN
|
||||||
|
ES_GET_STATE(J_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
ES_GET_STATE(K_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MIN
|
||||||
|
ES_GET_STATE(K_MIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
uint16_t endstop_change = live_state_local ^ old_live_state_local;
|
uint16_t endstop_change = live_state_local ^ old_live_state_local;
|
||||||
#define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S))
|
#define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S))
|
||||||
|
@ -1061,6 +1317,24 @@ void Endstops::update() {
|
||||||
#if HAS_Z4_MAX
|
#if HAS_Z4_MAX
|
||||||
ES_REPORT_CHANGE(Z4_MAX);
|
ES_REPORT_CHANGE(Z4_MAX);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MIN
|
||||||
|
ES_REPORT_CHANGE(I_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_I_MAX
|
||||||
|
ES_REPORT_CHANGE(I_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MIN
|
||||||
|
ES_REPORT_CHANGE(J_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MAX
|
||||||
|
ES_REPORT_CHANGE(J_MAX);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MIN
|
||||||
|
ES_REPORT_CHANGE(K_MIN);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MAX
|
||||||
|
ES_REPORT_CHANGE(K_MAX);
|
||||||
|
#endif
|
||||||
SERIAL_ECHOLNPGM("\n");
|
SERIAL_ECHOLNPGM("\n");
|
||||||
analogWrite(pin_t(LED_PIN), local_LED_status);
|
analogWrite(pin_t(LED_PIN), local_LED_status);
|
||||||
local_LED_status ^= 255;
|
local_LED_status ^= 255;
|
||||||
|
|
|
@ -39,6 +39,12 @@ enum EndstopEnum : char {
|
||||||
_ES_ITEM(HAS_Y_MAX, Y_MAX)
|
_ES_ITEM(HAS_Y_MAX, Y_MAX)
|
||||||
_ES_ITEM(HAS_Z_MIN, Z_MIN)
|
_ES_ITEM(HAS_Z_MIN, Z_MIN)
|
||||||
_ES_ITEM(HAS_Z_MAX, Z_MAX)
|
_ES_ITEM(HAS_Z_MAX, Z_MAX)
|
||||||
|
_ES_ITEM(HAS_I_MIN, I_MIN)
|
||||||
|
_ES_ITEM(HAS_I_MAX, I_MAX)
|
||||||
|
_ES_ITEM(HAS_J_MIN, J_MIN)
|
||||||
|
_ES_ITEM(HAS_J_MAX, J_MAX)
|
||||||
|
_ES_ITEM(HAS_K_MIN, K_MIN)
|
||||||
|
_ES_ITEM(HAS_K_MAX, K_MAX)
|
||||||
|
|
||||||
// Extra Endstops for XYZ
|
// Extra Endstops for XYZ
|
||||||
#if ENABLED(X_DUAL_ENDSTOPS)
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
|
|
@ -89,7 +89,7 @@ bool relative_mode; // = false;
|
||||||
#define Z_INIT_POS Z_HOME_POS
|
#define Z_INIT_POS Z_HOME_POS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS);
|
xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Cartesian Destination
|
* Cartesian Destination
|
||||||
|
@ -143,7 +143,7 @@ xyz_pos_t cartes;
|
||||||
|
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
|
|
||||||
abc_pos_t delta;
|
abce_pos_t delta;
|
||||||
|
|
||||||
#if HAS_SCARA_OFFSET
|
#if HAS_SCARA_OFFSET
|
||||||
abc_pos_t scara_home_offset;
|
abc_pos_t scara_home_offset;
|
||||||
|
@ -196,7 +196,14 @@ inline void report_more_positions() {
|
||||||
inline void report_logical_position(const xyze_pos_t &rpos) {
|
inline void report_logical_position(const xyze_pos_t &rpos) {
|
||||||
const xyze_pos_t lpos = rpos.asLogical();
|
const xyze_pos_t lpos = rpos.asLogical();
|
||||||
SERIAL_ECHOPAIR_P(
|
SERIAL_ECHOPAIR_P(
|
||||||
LIST_N(DOUBLE(LINEAR_AXES), X_LBL, lpos.x, SP_Y_LBL, lpos.y, SP_Z_LBL, lpos.z)
|
LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
|
X_LBL, lpos.x,
|
||||||
|
SP_Y_LBL, lpos.y,
|
||||||
|
SP_Z_LBL, lpos.z,
|
||||||
|
SP_I_LBL, lpos.i,
|
||||||
|
SP_J_LBL, lpos.j,
|
||||||
|
SP_K_LBL, lpos.k
|
||||||
|
)
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
, SP_E_LBL, lpos.e
|
, SP_E_LBL, lpos.e
|
||||||
#endif
|
#endif
|
||||||
|
@ -209,7 +216,10 @@ void report_real_position() {
|
||||||
get_cartesian_from_steppers();
|
get_cartesian_from_steppers();
|
||||||
xyze_pos_t npos = LOGICAL_AXIS_ARRAY(
|
xyze_pos_t npos = LOGICAL_AXIS_ARRAY(
|
||||||
planner.get_axis_position_mm(E_AXIS),
|
planner.get_axis_position_mm(E_AXIS),
|
||||||
cartes.x, cartes.y, cartes.z
|
cartes.x, cartes.y, cartes.z,
|
||||||
|
planner.get_axis_position_mm(I_AXIS),
|
||||||
|
planner.get_axis_position_mm(J_AXIS),
|
||||||
|
planner.get_axis_position_mm(K_AXIS)
|
||||||
);
|
);
|
||||||
|
|
||||||
TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true));
|
TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(npos, true));
|
||||||
|
@ -334,20 +344,21 @@ void sync_plan_position() {
|
||||||
void get_cartesian_from_steppers() {
|
void get_cartesian_from_steppers() {
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
forward_kinematics(planner.get_axis_positions_mm());
|
forward_kinematics(planner.get_axis_positions_mm());
|
||||||
#else
|
#elif IS_SCARA
|
||||||
#if IS_SCARA
|
|
||||||
forward_kinematics(
|
forward_kinematics(
|
||||||
planner.get_axis_position_degrees(A_AXIS)
|
planner.get_axis_position_degrees(A_AXIS), planner.get_axis_position_degrees(B_AXIS)
|
||||||
, planner.get_axis_position_degrees(B_AXIS)
|
OPTARG(AXEL_TPARA, planner.get_axis_position_degrees(C_AXIS))
|
||||||
#if ENABLED(AXEL_TPARA)
|
|
||||||
, planner.get_axis_position_degrees(C_AXIS)
|
|
||||||
#endif
|
|
||||||
);
|
);
|
||||||
#else
|
|
||||||
cartes.x = planner.get_axis_position_mm(X_AXIS);
|
|
||||||
cartes.y = planner.get_axis_position_mm(Y_AXIS);
|
|
||||||
#endif
|
|
||||||
cartes.z = planner.get_axis_position_mm(Z_AXIS);
|
cartes.z = planner.get_axis_position_mm(Z_AXIS);
|
||||||
|
#else
|
||||||
|
LINEAR_AXIS_CODE(
|
||||||
|
cartes.x = planner.get_axis_position_mm(X_AXIS),
|
||||||
|
cartes.y = planner.get_axis_position_mm(Y_AXIS),
|
||||||
|
cartes.z = planner.get_axis_position_mm(Z_AXIS),
|
||||||
|
cartes.i = planner.get_axis_position_mm(I_AXIS),
|
||||||
|
cartes.j = planner.get_axis_position_mm(J_AXIS),
|
||||||
|
cartes.k = planner.get_axis_position_mm(K_AXIS)
|
||||||
|
);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -366,13 +377,9 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
|
||||||
get_cartesian_from_steppers();
|
get_cartesian_from_steppers();
|
||||||
xyze_pos_t pos = cartes;
|
xyze_pos_t pos = cartes;
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
TERN_(HAS_EXTRUDERS, pos.e = planner.get_axis_position_mm(E_AXIS));
|
||||||
pos.e = planner.get_axis_position_mm(E_AXIS);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAS_POSITION_MODIFIERS
|
TERN_(HAS_POSITION_MODIFIERS, planner.unapply_modifiers(pos, true));
|
||||||
planner.unapply_modifiers(pos, true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (axis == ALL_AXES_ENUM)
|
if (axis == ALL_AXES_ENUM)
|
||||||
current_position = pos;
|
current_position = pos;
|
||||||
|
@ -385,7 +392,7 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) {
|
||||||
* (or from wherever it has been told it is located).
|
* (or from wherever it has been told it is located).
|
||||||
*/
|
*/
|
||||||
void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) {
|
void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) {
|
||||||
planner.buffer_line(current_position, fr_mm_s, active_extruder);
|
planner.buffer_line(current_position, fr_mm_s);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
|
@ -411,7 +418,7 @@ void line_to_current_position(const_feedRate_t fr_mm_s/*=feedrate_mm_s*/) {
|
||||||
#else
|
#else
|
||||||
if (current_position == destination) return;
|
if (current_position == destination) return;
|
||||||
|
|
||||||
planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
|
planner.buffer_line(destination, scaled_fr_mm_s);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
current_position = destination;
|
current_position = destination;
|
||||||
|
@ -449,25 +456,26 @@ void _internal_move_to_destination(const_feedRate_t fr_mm_s/*=0.0f*/
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Plan a move to (X, Y, Z) with separation of the XY and Z components.
|
* Plan a move to (X, Y, Z, [I, [J, [K]]]) and set the current_position
|
||||||
|
* Plan a move to (X, Y, Z) with separation of Z from other components.
|
||||||
*
|
*
|
||||||
* - If Z is moving up, the Z move is done before XY.
|
* - If Z is moving up, the Z move is done before XY, etc.
|
||||||
* - If Z is moving down, the Z move is done after XY.
|
* - If Z is moving down, the Z move is done after XY, etc.
|
||||||
* - Delta may lower Z first to get into the free motion zone.
|
* - Delta may lower Z first to get into the free motion zone.
|
||||||
* - Before returning, wait for the planner buffer to empty.
|
* - Before returning, wait for the planner buffer to empty.
|
||||||
*/
|
*/
|
||||||
void do_blocking_move_to(
|
void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
LINEAR_AXIS_LIST(const float rx, const float ry, const float rz),
|
|
||||||
const_feedRate_t fr_mm_s/*=0.0f*/
|
|
||||||
) {
|
|
||||||
DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING));
|
DEBUG_SECTION(log_move, "do_blocking_move_to", DEBUGGING(LEVELING));
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_LIST(rx, ry, rz));
|
if (DEBUGGING(LEVELING)) DEBUG_XYZ("> ", LINEAR_AXIS_ARGS());
|
||||||
|
|
||||||
const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS),
|
const feedRate_t xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S);
|
||||||
xy_feedrate = fr_mm_s ?: feedRate_t(XY_PROBE_FEEDRATE_MM_S);
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
const feedRate_t z_feedrate = fr_mm_s ?: homing_feedrate(Z_AXIS);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if EITHER(DELTA, IS_SCARA)
|
#if EITHER(DELTA, IS_SCARA)
|
||||||
if (!position_is_reachable(rx, ry)) return;
|
if (!position_is_reachable(x, y)) return;
|
||||||
destination = current_position; // sync destination at the start
|
destination = current_position; // sync destination at the start
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -479,8 +487,8 @@ void do_blocking_move_to(
|
||||||
|
|
||||||
// when in the danger zone
|
// when in the danger zone
|
||||||
if (current_position.z > delta_clip_start_height) {
|
if (current_position.z > delta_clip_start_height) {
|
||||||
if (rz > delta_clip_start_height) { // staying in the danger zone
|
if (z > delta_clip_start_height) { // staying in the danger zone
|
||||||
destination.set(rx, ry, rz); // move directly (uninterpolated)
|
destination.set(x, y, z); // move directly (uninterpolated)
|
||||||
prepare_internal_fast_move_to_destination(); // set current_position from destination
|
prepare_internal_fast_move_to_destination(); // set current_position from destination
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
|
if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
|
||||||
return;
|
return;
|
||||||
|
@ -490,18 +498,18 @@ void do_blocking_move_to(
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
|
if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rz > current_position.z) { // raising?
|
if (z > current_position.z) { // raising?
|
||||||
destination.z = rz;
|
destination.z = z;
|
||||||
prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination
|
prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
|
||||||
}
|
}
|
||||||
|
|
||||||
destination.set(rx, ry);
|
destination.set(x, y);
|
||||||
prepare_internal_move_to_destination(); // set current_position from destination
|
prepare_internal_move_to_destination(); // set current_position from destination
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
|
if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
|
||||||
|
|
||||||
if (rz < current_position.z) { // lowering?
|
if (z < current_position.z) { // lowering?
|
||||||
destination.z = rz;
|
destination.z = z;
|
||||||
prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination
|
prepare_internal_fast_move_to_destination(z_feedrate); // set current_position from destination
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
|
||||||
}
|
}
|
||||||
|
@ -509,36 +517,40 @@ void do_blocking_move_to(
|
||||||
#elif IS_SCARA
|
#elif IS_SCARA
|
||||||
|
|
||||||
// If Z needs to raise, do it before moving XY
|
// If Z needs to raise, do it before moving XY
|
||||||
if (destination.z < rz) {
|
if (destination.z < z) {
|
||||||
destination.z = rz;
|
destination.z = z;
|
||||||
prepare_internal_fast_move_to_destination(z_feedrate);
|
prepare_internal_fast_move_to_destination(z_feedrate);
|
||||||
}
|
}
|
||||||
|
|
||||||
destination.set(rx, ry);
|
destination.set(x, y);
|
||||||
prepare_internal_fast_move_to_destination(xy_feedrate);
|
prepare_internal_fast_move_to_destination(xy_feedrate);
|
||||||
|
|
||||||
// If Z needs to lower, do it after moving XY
|
// If Z needs to lower, do it after moving XY
|
||||||
if (destination.z > rz) {
|
if (destination.z > z) {
|
||||||
destination.z = rz;
|
destination.z = z;
|
||||||
prepare_internal_fast_move_to_destination(z_feedrate);
|
prepare_internal_fast_move_to_destination(z_feedrate);
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
// If Z needs to raise, do it before moving XY
|
// If Z needs to raise, do it before moving XY
|
||||||
if (current_position.z < rz) {
|
if (current_position.z < z) {
|
||||||
current_position.z = rz;
|
current_position.z = z;
|
||||||
line_to_current_position(z_feedrate);
|
line_to_current_position(z_feedrate);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
current_position.set(rx, ry);
|
current_position.set(x, y);
|
||||||
line_to_current_position(xy_feedrate);
|
line_to_current_position(xy_feedrate);
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
// If Z needs to lower, do it after moving XY
|
// If Z needs to lower, do it after moving XY
|
||||||
if (current_position.z > rz) {
|
if (current_position.z > z) {
|
||||||
current_position.z = rz;
|
current_position.z = z;
|
||||||
line_to_current_position(z_feedrate);
|
line_to_current_position(z_feedrate);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -546,53 +558,94 @@ void do_blocking_move_to(
|
||||||
}
|
}
|
||||||
|
|
||||||
void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i), fr_mm_s);
|
do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, current_position.z, current_position.i, current_position.j, current_position.k), fr_mm_s);
|
||||||
}
|
}
|
||||||
void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s);
|
do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
|
||||||
}
|
}
|
||||||
void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
do_blocking_move_to(LINEAR_AXIS_LIST(raw.x, raw.y, raw.z), fr_mm_s);
|
do_blocking_move_to(LINEAR_AXIS_ELEM(raw), fr_mm_s);
|
||||||
}
|
}
|
||||||
|
|
||||||
void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
|
void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
do_blocking_move_to(
|
do_blocking_move_to(
|
||||||
LINEAR_AXIS_LIST(rx, current_position.y, current_position.z),
|
LINEAR_AXIS_LIST(rx, current_position.y, current_position.z, current_position.i, current_position.j, current_position.k),
|
||||||
fr_mm_s
|
fr_mm_s
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
|
|
||||||
|
#if HAS_Y_AXIS
|
||||||
|
void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
do_blocking_move_to(
|
do_blocking_move_to(
|
||||||
LINEAR_AXIS_LIST(current_position.x, ry, current_position.z),
|
LINEAR_AXIS_LIST(current_position.x, ry, current_position.z, current_position.i, current_position.j, current_position.k),
|
||||||
fr_mm_s
|
fr_mm_s
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) {
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
do_blocking_move_to_xy_z(current_position, rz, fr_mm_s);
|
do_blocking_move_to_xy_z(current_position, rz, fr_mm_s);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
|
#if LINEAR_AXES == 4
|
||||||
|
void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
|
do_blocking_move_to(raw.x, raw.y, raw.z, i, fr_mm_s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to_xyz_i(current_position, ri, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
|
do_blocking_move_to(raw.x, raw.y, raw.z, i, raw.j, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to_xyzi_j(current_position, rj, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
|
do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, j, fr_mm_s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to_xyzij_k(current_position, rk, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
|
do_blocking_move_to(raw.x, raw.y, raw.z, raw.i, raw.j, k, fr_mm_s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Y_AXIS
|
||||||
|
void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s/*=0.0*/) {
|
||||||
do_blocking_move_to(
|
do_blocking_move_to(
|
||||||
LINEAR_AXIS_LIST(rx, ry, current_position.z),
|
LINEAR_AXIS_LIST(rx, ry, current_position.z, current_position.i, current_position.j, current_position.k),
|
||||||
fr_mm_s
|
fr_mm_s
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s);
|
do_blocking_move_to_xy(raw.x, raw.y, fr_mm_s);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
#if HAS_Z_AXIS
|
||||||
|
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s/*=0.0f*/) {
|
||||||
do_blocking_move_to(
|
do_blocking_move_to(
|
||||||
LINEAR_AXIS_LIST(raw.x, raw.y, z),
|
LINEAR_AXIS_LIST(raw.x, raw.y, z, current_position.i, current_position.j, current_position.k),
|
||||||
fr_mm_s
|
fr_mm_s
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) {
|
||||||
void do_z_clearance(const_float_t zclear, const bool lower_allowed/*=false*/) {
|
|
||||||
float zdest = zclear;
|
float zdest = zclear;
|
||||||
if (!lower_allowed) NOLESS(zdest, current_position.z);
|
if (!lower_allowed) NOLESS(zdest, current_position.z);
|
||||||
do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS)));
|
do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), TERN(HAS_BED_PROBE, z_probe_fast_mm_s, homing_feedrate(Z_AXIS)));
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Prepare to do endstop or probe moves with custom feedrates.
|
// Prepare to do endstop or probe moves with custom feedrates.
|
||||||
|
@ -618,8 +671,8 @@ void restore_feedrate_and_scaling() {
|
||||||
// Software Endstops are based on the configured limits.
|
// Software Endstops are based on the configured limits.
|
||||||
soft_endstops_t soft_endstop = {
|
soft_endstops_t soft_endstop = {
|
||||||
true, false,
|
true, false,
|
||||||
LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS),
|
LINEAR_AXIS_ARRAY(X_MIN_POS, Y_MIN_POS, Z_MIN_POS, I_MIN_POS, J_MIN_POS, K_MIN_POS),
|
||||||
LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS)
|
LINEAR_AXIS_ARRAY(X_MAX_BED, Y_MAX_BED, Z_MAX_POS, I_MAX_POS, J_MAX_POS, K_MAX_POS)
|
||||||
};
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -746,6 +799,7 @@ void restore_feedrate_and_scaling() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAS_Y_AXIS
|
||||||
if (axis_was_homed(Y_AXIS)) {
|
if (axis_was_homed(Y_AXIS)) {
|
||||||
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y)
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y)
|
||||||
NOLESS(target.y, soft_endstop.min.y);
|
NOLESS(target.y, soft_endstop.min.y);
|
||||||
|
@ -754,9 +808,11 @@ void restore_feedrate_and_scaling() {
|
||||||
NOMORE(target.y, soft_endstop.max.y);
|
NOMORE(target.y, soft_endstop.max.y);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
if (axis_was_homed(Z_AXIS)) {
|
if (axis_was_homed(Z_AXIS)) {
|
||||||
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z)
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z)
|
||||||
NOLESS(target.z, soft_endstop.min.z);
|
NOLESS(target.z, soft_endstop.min.z);
|
||||||
|
@ -765,6 +821,37 @@ void restore_feedrate_and_scaling() {
|
||||||
NOMORE(target.z, soft_endstop.max.z);
|
NOMORE(target.z, soft_endstop.max.z);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 // TODO (DerAndere): Find out why this was missing / removed
|
||||||
|
if (axis_was_homed(I_AXIS)) {
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_I)
|
||||||
|
NOLESS(target.i, soft_endstop.min.i);
|
||||||
|
#endif
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_I)
|
||||||
|
NOMORE(target.i, soft_endstop.max.i);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
if (axis_was_homed(J_AXIS)) {
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_J)
|
||||||
|
NOLESS(target.j, soft_endstop.min.j);
|
||||||
|
#endif
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_J)
|
||||||
|
NOMORE(target.j, soft_endstop.max.j);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
if (axis_was_homed(K_AXIS)) {
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_K)
|
||||||
|
NOLESS(target.k, soft_endstop.min.k);
|
||||||
|
#endif
|
||||||
|
#if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MAX_SOFTWARE_ENDSTOP_K)
|
||||||
|
NOMORE(target.k, soft_endstop.max.k);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#else // !HAS_SOFTWARE_ENDSTOPS
|
#else // !HAS_SOFTWARE_ENDSTOPS
|
||||||
|
@ -824,7 +911,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
|
|
||||||
// If the move is only in Z/E don't split up the move
|
// If the move is only in Z/E don't split up the move
|
||||||
if (!diff.x && !diff.y) {
|
if (!diff.x && !diff.y) {
|
||||||
planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
|
planner.buffer_line(destination, scaled_fr_mm_s);
|
||||||
return false; // caller will update current_position
|
return false; // caller will update current_position
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -880,15 +967,11 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
while (--segments) {
|
while (--segments) {
|
||||||
segment_idle(next_idle_ms);
|
segment_idle(next_idle_ms);
|
||||||
raw += segment_distance;
|
raw += segment_distance;
|
||||||
if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm
|
if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break;
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
|
||||||
)) break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Ensure last segment arrives at target location.
|
// Ensure last segment arrives at target location.
|
||||||
planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm
|
planner.buffer_line(destination, scaled_fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration));
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
|
||||||
);
|
|
||||||
|
|
||||||
return false; // caller will update current_position
|
return false; // caller will update current_position
|
||||||
}
|
}
|
||||||
|
@ -910,7 +993,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
|
|
||||||
// If the move is only in Z/E don't split up the move
|
// If the move is only in Z/E don't split up the move
|
||||||
if (!diff.x && !diff.y) {
|
if (!diff.x && !diff.y) {
|
||||||
planner.buffer_line(destination, fr_mm_s, active_extruder);
|
planner.buffer_line(destination, fr_mm_s);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -947,18 +1030,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
while (--segments) {
|
while (--segments) {
|
||||||
segment_idle(next_idle_ms);
|
segment_idle(next_idle_ms);
|
||||||
raw += segment_distance;
|
raw += segment_distance;
|
||||||
if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm
|
if (!planner.buffer_line(raw, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration))) break;
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
|
||||||
)) break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Since segment_distance is only approximate,
|
// Since segment_distance is only approximate,
|
||||||
// the final move must be to the exact destination.
|
// the final move must be to the exact destination.
|
||||||
planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm
|
planner.buffer_line(destination, fr_mm_s, active_extruder, cartesian_segment_mm OPTARG(SCARA_FEEDRATE_SCALING, inv_duration));
|
||||||
#if ENABLED(SCARA_FEEDRATE_SCALING)
|
|
||||||
, inv_duration
|
|
||||||
#endif
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // SEGMENT_LEVELED_MOVES
|
#endif // SEGMENT_LEVELED_MOVES
|
||||||
|
@ -998,7 +1075,7 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
}
|
}
|
||||||
#endif // HAS_MESH
|
#endif // HAS_MESH
|
||||||
|
|
||||||
planner.buffer_line(destination, scaled_fr_mm_s, active_extruder);
|
planner.buffer_line(destination, scaled_fr_mm_s);
|
||||||
return false; // caller will update current_position
|
return false; // caller will update current_position
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1080,12 +1157,12 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
// Un-park the active extruder
|
// Un-park the active extruder
|
||||||
//
|
//
|
||||||
const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS];
|
const feedRate_t fr_zfast = planner.settings.max_feedrate_mm_s[Z_AXIS];
|
||||||
#define CURPOS current_position
|
|
||||||
#define RAISED raised_parked_position
|
|
||||||
// 1. Move to the raised parked XYZ. Presumably the tool is already at XY.
|
// 1. Move to the raised parked XYZ. Presumably the tool is already at XY.
|
||||||
if (planner.buffer_line(RAISED.x, RAISED.y, RAISED.z, CURPOS.e, fr_zfast, active_extruder)) {
|
xyze_pos_t raised = raised_parked_position; raised.e = current_position.e;
|
||||||
|
if (planner.buffer_line(raised, fr_zfast)) {
|
||||||
// 2. Move to the current native XY and raised Z. Presumably this is a null move.
|
// 2. Move to the current native XY and raised Z. Presumably this is a null move.
|
||||||
if (planner.buffer_line(CURPOS.x, CURPOS.y, RAISED.z, CURPOS.e, PLANNER_XY_FEEDRATE(), active_extruder)) {
|
xyze_pos_t curpos = current_position; curpos.z = raised_parked_position.z;
|
||||||
|
if (planner.buffer_line(curpos, PLANNER_XY_FEEDRATE())) {
|
||||||
// 3. Lower Z back down
|
// 3. Lower Z back down
|
||||||
line_to_current_position(fr_zfast);
|
line_to_current_position(fr_zfast);
|
||||||
}
|
}
|
||||||
|
@ -1099,21 +1176,24 @@ FORCE_INLINE void segment_idle(millis_t &next_idle_ms) {
|
||||||
case DXC_MIRRORED_MODE:
|
case DXC_MIRRORED_MODE:
|
||||||
case DXC_DUPLICATION_MODE:
|
case DXC_DUPLICATION_MODE:
|
||||||
if (active_extruder == 0) {
|
if (active_extruder == 0) {
|
||||||
xyze_pos_t new_pos = current_position;
|
// Restore planner to parked head (T1) X position
|
||||||
|
xyze_pos_t pos_now = current_position;
|
||||||
|
pos_now.x = inactive_extruder_x;
|
||||||
|
planner.set_position_mm(pos_now);
|
||||||
|
|
||||||
|
// Keep the same X or add the duplication X offset
|
||||||
|
xyze_pos_t new_pos = pos_now;
|
||||||
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE)
|
if (dual_x_carriage_mode == DXC_DUPLICATION_MODE)
|
||||||
new_pos.x += duplicate_extruder_x_offset;
|
new_pos.x += duplicate_extruder_x_offset;
|
||||||
else
|
|
||||||
new_pos.x = inactive_extruder_x;
|
// Move duplicate extruder into the correct position
|
||||||
// Move duplicate extruder into correct duplication position.
|
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x);
|
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Set planner X", inactive_extruder_x, " ... Line to X", new_pos.x);
|
||||||
planner.set_position_mm(inactive_extruder_x, current_position.y, current_position.z, current_position.e);
|
|
||||||
if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break;
|
if (!planner.buffer_line(new_pos, planner.settings.max_feedrate_mm_s[X_AXIS], 1)) break;
|
||||||
|
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
sync_plan_position();
|
|
||||||
|
|
||||||
set_duplication_enabled(true);
|
sync_plan_position(); // Extra sync for good measure
|
||||||
idex_set_parked(false);
|
set_duplication_enabled(true); // Enable Duplication
|
||||||
|
idex_set_parked(false); // No longer parked
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)");
|
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("set_duplication_enabled(true)\nidex_set_parked(false)");
|
||||||
}
|
}
|
||||||
else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0");
|
else if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Active extruder not 0");
|
||||||
|
@ -1207,22 +1287,24 @@ void prepare_line_to_destination() {
|
||||||
};
|
};
|
||||||
// Clear test bits that are trusted
|
// Clear test bits that are trusted
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
set_should(axis_bits, X_AXIS),
|
set_should(axis_bits, X_AXIS), set_should(axis_bits, Y_AXIS), set_should(axis_bits, Z_AXIS),
|
||||||
set_should(axis_bits, Y_AXIS),
|
set_should(axis_bits, I_AXIS), set_should(axis_bits, J_AXIS), set_should(axis_bits, K_AXIS)
|
||||||
set_should(axis_bits, Z_AXIS)
|
|
||||||
);
|
);
|
||||||
return axis_bits;
|
return axis_bits;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) {
|
bool homing_needed_error(linear_axis_bits_t axis_bits/*=linear_bits*/) {
|
||||||
if ((axis_bits = axes_should_home(axis_bits))) {
|
if ((axis_bits = axes_should_home(axis_bits))) {
|
||||||
PGM_P home_first = GET_TEXT(MSG_HOME_FIRST);
|
PGM_P home_first = GET_TEXT(MSG_HOME_FIRST); // TODO: (DerAndere) Set this up for extra axes
|
||||||
char msg[strlen_P(home_first)+1];
|
char msg[strlen_P(home_first)+1];
|
||||||
sprintf_P(msg, home_first,
|
sprintf_P(msg, home_first,
|
||||||
LINEAR_AXIS_LIST(
|
LINEAR_AXIS_LIST(
|
||||||
TEST(axis_bits, X_AXIS) ? "X" : "",
|
TEST(axis_bits, X_AXIS) ? "X" : "",
|
||||||
TEST(axis_bits, Y_AXIS) ? "Y" : "",
|
TEST(axis_bits, Y_AXIS) ? "Y" : "",
|
||||||
TEST(axis_bits, Z_AXIS) ? "Z" : ""
|
TEST(axis_bits, Z_AXIS) ? "Z" : "",
|
||||||
|
TEST(axis_bits, I_AXIS) ? AXIS4_STR : "",
|
||||||
|
TEST(axis_bits, J_AXIS) ? AXIS5_STR : "",
|
||||||
|
TEST(axis_bits, K_AXIS) ? AXIS6_STR : ""
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
|
@ -1374,6 +1456,9 @@ void prepare_line_to_destination() {
|
||||||
case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break;
|
case X_AXIS: if (ENABLED(X_SPI_SENSORLESS)) endstops.tmc_spi_homing.x = false; break;
|
||||||
case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break;
|
case Y_AXIS: if (ENABLED(Y_SPI_SENSORLESS)) endstops.tmc_spi_homing.y = false; break;
|
||||||
case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break;
|
case Z_AXIS: if (ENABLED(Z_SPI_SENSORLESS)) endstops.tmc_spi_homing.z = false; break;
|
||||||
|
case I_AXIS: if (ENABLED(I_SPI_SENSORLESS)) endstops.tmc_spi_homing.i = false; break;
|
||||||
|
case J_AXIS: if (ENABLED(J_SPI_SENSORLESS)) endstops.tmc_spi_homing.j = false; break;
|
||||||
|
case K_AXIS: if (ENABLED(K_SPI_SENSORLESS)) endstops.tmc_spi_homing.k = false; break;
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1446,12 +1531,7 @@ void prepare_line_to_destination() {
|
||||||
|
|
||||||
// Set delta/cartesian axes directly
|
// Set delta/cartesian axes directly
|
||||||
target[axis] = distance; // The move will be towards the endstop
|
target[axis] = distance; // The move will be towards the endstop
|
||||||
planner.buffer_segment(target
|
planner.buffer_segment(target OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), home_fr_mm_s, active_extruder);
|
||||||
#if HAS_DIST_MM_ARG
|
|
||||||
, cart_dist_mm
|
|
||||||
#endif
|
|
||||||
, home_fr_mm_s, active_extruder
|
|
||||||
);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
|
@ -1531,6 +1611,30 @@ void prepare_line_to_destination() {
|
||||||
stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir;
|
stepperBackoutDir = INVERT_Z_DIR ? effectorBackoutDir : -effectorBackoutDir;
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef I_MICROSTEPS
|
||||||
|
case I_AXIS:
|
||||||
|
phasePerUStep = PHASE_PER_MICROSTEP(I);
|
||||||
|
phaseCurrent = stepperI.get_microstep_counter();
|
||||||
|
effectorBackoutDir = -I_HOME_DIR;
|
||||||
|
stepperBackoutDir = INVERT_I_DIR ? effectorBackoutDir : -effectorBackoutDir;
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#ifdef J_MICROSTEPS
|
||||||
|
case J_AXIS:
|
||||||
|
phasePerUStep = PHASE_PER_MICROSTEP(J);
|
||||||
|
phaseCurrent = stepperJ.get_microstep_counter();
|
||||||
|
effectorBackoutDir = -J_HOME_DIR;
|
||||||
|
stepperBackoutDir = INVERT_J_DIR ? effectorBackoutDir : -effectorBackoutDir;
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#ifdef K_MICROSTEPS
|
||||||
|
case K_AXIS:
|
||||||
|
phasePerUStep = PHASE_PER_MICROSTEP(K);
|
||||||
|
phaseCurrent = stepperK.get_microstep_counter();
|
||||||
|
effectorBackoutDir = -K_HOME_DIR;
|
||||||
|
stepperBackoutDir = INVERT_K_DIR ? effectorBackoutDir : -effectorBackoutDir;
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
default: return;
|
default: return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1583,11 +1687,18 @@ void prepare_line_to_destination() {
|
||||||
#else
|
#else
|
||||||
#define _CAN_HOME(A) (axis == _AXIS(A) && ( \
|
#define _CAN_HOME(A) (axis == _AXIS(A) && ( \
|
||||||
ENABLED(A##_SPI_SENSORLESS) \
|
ENABLED(A##_SPI_SENSORLESS) \
|
||||||
|| (_AXIS(A) == Z_AXIS && ENABLED(HOMING_Z_WITH_PROBE)) \
|
|| TERN0(HAS_Z_AXIS, TERN0(HOMING_Z_WITH_PROBE, _AXIS(A) == Z_AXIS)) \
|
||||||
|| TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \
|
|| TERN0(A##_HOME_TO_MIN, A##_MIN_PIN > -1) \
|
||||||
|| TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \
|
|| TERN0(A##_HOME_TO_MAX, A##_MAX_PIN > -1) \
|
||||||
))
|
))
|
||||||
if (!_CAN_HOME(X) && !_CAN_HOME(Y) && !_CAN_HOME(Z)) return;
|
if (LINEAR_AXIS_GANG(
|
||||||
|
!_CAN_HOME(X),
|
||||||
|
&& !_CAN_HOME(Y),
|
||||||
|
&& !_CAN_HOME(Z),
|
||||||
|
&& !_CAN_HOME(I),
|
||||||
|
&& !_CAN_HOME(J),
|
||||||
|
&& !_CAN_HOME(K))
|
||||||
|
) return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")");
|
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> homeaxis(", AS_CHAR(AXIS_CHAR(axis)), ")");
|
||||||
|
@ -1636,9 +1747,9 @@ void prepare_line_to_destination() {
|
||||||
|
|
||||||
// Determine if a homing bump will be done and the bumps distance
|
// Determine if a homing bump will be done and the bumps distance
|
||||||
// When homing Z with probe respect probe clearance
|
// When homing Z with probe respect probe clearance
|
||||||
const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(Z_AXIS));
|
const bool use_probe_bump = TERN0(HOMING_Z_WITH_PROBE, axis == Z_AXIS && home_bump_mm(axis));
|
||||||
const float bump = axis_home_dir * (
|
const float bump = axis_home_dir * (
|
||||||
use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(Z_AXIS)) : home_bump_mm(axis)
|
use_probe_bump ? _MAX(TERN0(HOMING_Z_WITH_PROBE, Z_CLEARANCE_BETWEEN_PROBES), home_bump_mm(axis)) : home_bump_mm(axis)
|
||||||
);
|
);
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|
|
@ -44,7 +44,7 @@ extern xyze_pos_t current_position, // High-level current tool position
|
||||||
|
|
||||||
// G60/G61 Position Save and Return
|
// G60/G61 Position Save and Return
|
||||||
#if SAVED_POSITIONS
|
#if SAVED_POSITIONS
|
||||||
extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3];
|
extern uint8_t saved_slots[(SAVED_POSITIONS + 7) >> 3]; // TODO: Add support for LINEAR_AXES >= 4
|
||||||
extern xyze_pos_t stored_position[SAVED_POSITIONS];
|
extern xyze_pos_t stored_position[SAVED_POSITIONS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -53,7 +53,7 @@ extern xyz_pos_t cartes;
|
||||||
|
|
||||||
// Until kinematics.cpp is created, declare this here
|
// Until kinematics.cpp is created, declare this here
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
extern abc_pos_t delta;
|
extern abce_pos_t delta;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_ABL_NOT_UBL
|
#if HAS_ABL_NOT_UBL
|
||||||
|
@ -75,16 +75,16 @@ extern xyz_pos_t cartes;
|
||||||
*/
|
*/
|
||||||
constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M;
|
constexpr xyz_feedrate_t homing_feedrate_mm_m = HOMING_FEEDRATE_MM_M;
|
||||||
FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) {
|
FORCE_INLINE feedRate_t homing_feedrate(const AxisEnum a) {
|
||||||
float v;
|
float v = TERN0(HAS_Z_AXIS, homing_feedrate_mm_m.z);
|
||||||
#if ENABLED(DELTA)
|
#if DISABLED(DELTA)
|
||||||
v = homing_feedrate_mm_m.z;
|
LINEAR_AXIS_CODE(
|
||||||
#else
|
if (a == X_AXIS) v = homing_feedrate_mm_m.x,
|
||||||
switch (a) {
|
else if (a == Y_AXIS) v = homing_feedrate_mm_m.y,
|
||||||
case X_AXIS: v = homing_feedrate_mm_m.x; break;
|
else if (a == Z_AXIS) v = homing_feedrate_mm_m.z,
|
||||||
case Y_AXIS: v = homing_feedrate_mm_m.y; break;
|
else if (a == I_AXIS) v = homing_feedrate_mm_m.i,
|
||||||
case Z_AXIS:
|
else if (a == J_AXIS) v = homing_feedrate_mm_m.j,
|
||||||
default: v = homing_feedrate_mm_m.z;
|
else if (a == K_AXIS) v = homing_feedrate_mm_m.k
|
||||||
}
|
);
|
||||||
#endif
|
#endif
|
||||||
return MMM_TO_MMS(v);
|
return MMM_TO_MMS(v);
|
||||||
}
|
}
|
||||||
|
@ -124,7 +124,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm
|
||||||
|
|
||||||
#define XYZ_DEFS(T, NAME, OPT) \
|
#define XYZ_DEFS(T, NAME, OPT) \
|
||||||
inline T NAME(const AxisEnum axis) { \
|
inline T NAME(const AxisEnum axis) { \
|
||||||
static const XYZval<T> NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT); \
|
static const XYZval<T> NAME##_P DEFS_PROGMEM = LINEAR_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT); \
|
||||||
return pgm_read_any(&NAME##_P[axis]); \
|
return pgm_read_any(&NAME##_P[axis]); \
|
||||||
}
|
}
|
||||||
XYZ_DEFS(float, base_min_pos, MIN_POS);
|
XYZ_DEFS(float, base_min_pos, MIN_POS);
|
||||||
|
@ -168,13 +168,36 @@ inline float home_bump_mm(const AxisEnum axis) {
|
||||||
TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x);
|
TERN_(MIN_SOFTWARE_ENDSTOP_X, amin = min.x);
|
||||||
TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x);
|
TERN_(MAX_SOFTWARE_ENDSTOP_X, amax = max.x);
|
||||||
break;
|
break;
|
||||||
|
#if HAS_Y_AXIS
|
||||||
case Y_AXIS:
|
case Y_AXIS:
|
||||||
TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
|
TERN_(MIN_SOFTWARE_ENDSTOP_Y, amin = min.y);
|
||||||
TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
|
TERN_(MAX_SOFTWARE_ENDSTOP_Y, amax = max.y);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
case Z_AXIS:
|
case Z_AXIS:
|
||||||
TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
|
TERN_(MIN_SOFTWARE_ENDSTOP_Z, amin = min.z);
|
||||||
TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
|
TERN_(MAX_SOFTWARE_ENDSTOP_Z, amax = max.z);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4 // TODO (DerAndere): Test for LINEAR_AXES >= 4
|
||||||
|
case I_AXIS:
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_I, amin = min.i);
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_I, amax = max.i);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
case J_AXIS:
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_J, amin = min.j);
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_J, amax = max.j);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
case K_AXIS:
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_K, amin = min.k);
|
||||||
|
TERN_(MIN_SOFTWARE_ENDSTOP_K, amax = max.k);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -298,32 +321,53 @@ inline void prepare_internal_move_to_destination(const_feedRate_t fr_mm_s=0.0f)
|
||||||
/**
|
/**
|
||||||
* Blocking movement and shorthand functions
|
* Blocking movement and shorthand functions
|
||||||
*/
|
*/
|
||||||
void do_blocking_move_to(
|
void do_blocking_move_to(LINEAR_AXIS_ARGS(const float), const_feedRate_t fr_mm_s=0.0f);
|
||||||
LINEAR_AXIS_LIST(const float rx, const float ry, const float rz),
|
|
||||||
const_feedRate_t fr_mm_s=0.0f
|
|
||||||
);
|
|
||||||
void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
||||||
void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
||||||
void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
|
||||||
void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to_x(const_float_t rx, const_feedRate_t fr_mm_s=0.0f);
|
||||||
void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
|
#if HAS_Y_AXIS
|
||||||
void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to_y(const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
void do_blocking_move_to_z(const_float_t rz, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
void do_blocking_move_to_i(const_float_t ri, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
void do_blocking_move_to_xyz_i(const xyze_pos_t &raw, const_float_t i, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
void do_blocking_move_to_j(const_float_t rj, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
void do_blocking_move_to_xyzi_j(const xyze_pos_t &raw, const_float_t j, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
void do_blocking_move_to_k(const_float_t rk, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
void do_blocking_move_to_xyzij_k(const xyze_pos_t &raw, const_float_t k, const_feedRate_t fr_mm_s=0.0f);
|
||||||
|
#endif
|
||||||
|
|
||||||
void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
|
#if HAS_Y_AXIS
|
||||||
void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
void do_blocking_move_to_xy(const_float_t rx, const_float_t ry, const_feedRate_t fr_mm_s=0.0f);
|
||||||
FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
|
void do_blocking_move_to_xy(const xy_pos_t &raw, const_feedRate_t fr_mm_s=0.0f);
|
||||||
FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
|
FORCE_INLINE void do_blocking_move_to_xy(const xyz_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
|
||||||
|
FORCE_INLINE void do_blocking_move_to_xy(const xyze_pos_t &raw, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy(xy_pos_t(raw), fr_mm_s); }
|
||||||
|
#endif
|
||||||
|
|
||||||
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f);
|
#if HAS_Z_AXIS
|
||||||
FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
|
void do_blocking_move_to_xy_z(const xy_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f);
|
||||||
FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
|
FORCE_INLINE void do_blocking_move_to_xy_z(const xyz_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
|
||||||
|
FORCE_INLINE void do_blocking_move_to_xy_z(const xyze_pos_t &raw, const_float_t z, const_feedRate_t fr_mm_s=0.0f) { do_blocking_move_to_xy_z(xy_pos_t(raw), z, fr_mm_s); }
|
||||||
|
#endif
|
||||||
|
|
||||||
void remember_feedrate_and_scaling();
|
void remember_feedrate_and_scaling();
|
||||||
void remember_feedrate_scaling_off();
|
void remember_feedrate_scaling_off();
|
||||||
void restore_feedrate_and_scaling();
|
void restore_feedrate_and_scaling();
|
||||||
|
|
||||||
void do_z_clearance(const_float_t zclear, const bool lower_allowed=false);
|
#if HAS_Z_AXIS
|
||||||
|
void do_z_clearance(const_float_t zclear, const bool lower_allowed=false);
|
||||||
|
#else
|
||||||
|
inline void do_z_clearance(float, bool=false) {}
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Homing and Trusted Axes
|
* Homing and Trusted Axes
|
||||||
|
@ -421,11 +465,27 @@ FORCE_INLINE bool all_axes_trusted() { return linear_bits
|
||||||
FORCE_INLINE void toNative(xyze_pos_t&) {}
|
FORCE_INLINE void toNative(xyze_pos_t&) {}
|
||||||
#endif
|
#endif
|
||||||
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
|
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
|
||||||
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
|
|
||||||
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
|
|
||||||
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
|
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
|
||||||
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
|
#if HAS_Y_AXIS
|
||||||
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
|
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
|
||||||
|
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
|
||||||
|
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define LOGICAL_I_POSITION(POS) NATIVE_TO_LOGICAL(POS, I_AXIS)
|
||||||
|
#define RAW_I_POSITION(POS) LOGICAL_TO_NATIVE(POS, I_AXIS)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define LOGICAL_J_POSITION(POS) NATIVE_TO_LOGICAL(POS, J_AXIS)
|
||||||
|
#define RAW_J_POSITION(POS) LOGICAL_TO_NATIVE(POS, J_AXIS)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define LOGICAL_K_POSITION(POS) NATIVE_TO_LOGICAL(POS, K_AXIS)
|
||||||
|
#define RAW_K_POSITION(POS) LOGICAL_TO_NATIVE(POS, K_AXIS)
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* position_is_reachable family of functions
|
* position_is_reachable family of functions
|
||||||
|
|
|
@ -1310,7 +1310,7 @@ void Planner::recalculate() {
|
||||||
*/
|
*/
|
||||||
void Planner::check_axes_activity() {
|
void Planner::check_axes_activity() {
|
||||||
|
|
||||||
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E)
|
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z , DISABLE_I , DISABLE_J , DISABLE_K, DISABLE_E)
|
||||||
xyze_bool_t axis_active = { false };
|
xyze_bool_t axis_active = { false };
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1342,14 +1342,17 @@ void Planner::check_axes_activity() {
|
||||||
TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure);
|
TERN_(HAS_HEATER_2, tail_e_to_p_pressure = block->e_to_p_pressure);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_E)
|
#if ANY(DISABLE_X, DISABLE_Y, DISABLE_Z, DISABLE_I, DISABLE_J, DISABLE_K, DISABLE_E)
|
||||||
for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
|
for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
|
||||||
block_t *block = &block_buffer[b];
|
block_t *block = &block_buffer[b];
|
||||||
LOGICAL_AXIS_CODE(
|
LOGICAL_AXIS_CODE(
|
||||||
if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true,
|
if (TERN0(DISABLE_E, block->steps.e)) axis_active.e = true,
|
||||||
if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true,
|
if (TERN0(DISABLE_X, block->steps.x)) axis_active.x = true,
|
||||||
if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true,
|
if (TERN0(DISABLE_Y, block->steps.y)) axis_active.y = true,
|
||||||
if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true
|
if (TERN0(DISABLE_Z, block->steps.z)) axis_active.z = true,
|
||||||
|
if (TERN0(DISABLE_I, block->steps.i)) axis_active.i = true,
|
||||||
|
if (TERN0(DISABLE_J, block->steps.j)) axis_active.j = true,
|
||||||
|
if (TERN0(DISABLE_K, block->steps.k)) axis_active.k = true
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1375,7 +1378,10 @@ void Planner::check_axes_activity() {
|
||||||
if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(),
|
if (TERN0(DISABLE_E, !axis_active.e)) disable_e_steppers(),
|
||||||
if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(),
|
if (TERN0(DISABLE_X, !axis_active.x)) DISABLE_AXIS_X(),
|
||||||
if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(),
|
if (TERN0(DISABLE_Y, !axis_active.y)) DISABLE_AXIS_Y(),
|
||||||
if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z()
|
if (TERN0(DISABLE_Z, !axis_active.z)) DISABLE_AXIS_Z(),
|
||||||
|
if (TERN0(DISABLE_I, !axis_active.i)) DISABLE_AXIS_I(),
|
||||||
|
if (TERN0(DISABLE_J, !axis_active.j)) DISABLE_AXIS_J(),
|
||||||
|
if (TERN0(DISABLE_K, !axis_active.k)) DISABLE_AXIS_K()
|
||||||
);
|
);
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -1445,7 +1451,7 @@ void Planner::check_axes_activity() {
|
||||||
float high = 0.0;
|
float high = 0.0;
|
||||||
for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
|
for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
|
||||||
block_t *block = &block_buffer[b];
|
block_t *block = &block_buffer[b];
|
||||||
if (block->steps.x || block->steps.y || block->steps.z) {
|
if (LINEAR_AXIS_GANG(block->steps.x, || block->steps.y, || block->steps.z, block->steps.i, || block->steps.j, || block->steps.k)) {
|
||||||
const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
|
const float se = (float)block->steps.e / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
|
||||||
NOLESS(high, se);
|
NOLESS(high, se);
|
||||||
}
|
}
|
||||||
|
@ -1831,7 +1837,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
de = target.e - position.e,
|
de = target.e - position.e,
|
||||||
da = target.a - position.a,
|
da = target.a - position.a,
|
||||||
db = target.b - position.b,
|
db = target.b - position.b,
|
||||||
dc = target.c - position.c
|
dc = target.c - position.c,
|
||||||
|
di = target.i - position.i,
|
||||||
|
dj = target.j - position.j,
|
||||||
|
dk = target.k - position.k
|
||||||
);
|
);
|
||||||
|
|
||||||
/* <-- add a slash to enable
|
/* <-- add a slash to enable
|
||||||
|
@ -1910,7 +1919,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
if (da < 0) SBI(dm, X_AXIS),
|
if (da < 0) SBI(dm, X_AXIS),
|
||||||
if (db < 0) SBI(dm, Y_AXIS),
|
if (db < 0) SBI(dm, Y_AXIS),
|
||||||
if (dc < 0) SBI(dm, Z_AXIS)
|
if (dc < 0) SBI(dm, Z_AXIS),
|
||||||
|
if (di < 0) SBI(dm, I_AXIS),
|
||||||
|
if (dj < 0) SBI(dm, J_AXIS),
|
||||||
|
if (dk < 0) SBI(dm, K_AXIS)
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
|
@ -1951,7 +1963,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
block->steps.set(ABS(da), ABS(db), ABS(dc));
|
block->steps.set(ABS(da), ABS(db), ABS(dc));
|
||||||
#else
|
#else
|
||||||
// default non-h-bot planning
|
// default non-h-bot planning
|
||||||
block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc)));
|
block->steps.set(LINEAR_AXIS_LIST(ABS(da), ABS(db), ABS(dc), ABS(di), ABS(dj), ABS(dk)));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1997,7 +2009,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
steps_dist_mm.a = da * steps_to_mm[A_AXIS],
|
steps_dist_mm.a = da * steps_to_mm[A_AXIS],
|
||||||
steps_dist_mm.b = db * steps_to_mm[B_AXIS],
|
steps_dist_mm.b = db * steps_to_mm[B_AXIS],
|
||||||
steps_dist_mm.c = dc * steps_to_mm[C_AXIS]
|
steps_dist_mm.c = dc * steps_to_mm[C_AXIS],
|
||||||
|
steps_dist_mm.i = di * steps_to_mm[I_AXIS],
|
||||||
|
steps_dist_mm.j = dj * steps_to_mm[J_AXIS],
|
||||||
|
steps_dist_mm.k = dk * steps_to_mm[K_AXIS]
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2010,7 +2025,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
if (true LINEAR_AXIS_GANG(
|
if (true LINEAR_AXIS_GANG(
|
||||||
&& block->steps.a < MIN_STEPS_PER_SEGMENT,
|
&& block->steps.a < MIN_STEPS_PER_SEGMENT,
|
||||||
&& block->steps.b < MIN_STEPS_PER_SEGMENT,
|
&& block->steps.b < MIN_STEPS_PER_SEGMENT,
|
||||||
&& block->steps.c < MIN_STEPS_PER_SEGMENT
|
&& block->steps.c < MIN_STEPS_PER_SEGMENT,
|
||||||
|
&& block->steps.i < MIN_STEPS_PER_SEGMENT,
|
||||||
|
&& block->steps.j < MIN_STEPS_PER_SEGMENT,
|
||||||
|
&& block->steps.k < MIN_STEPS_PER_SEGMENT
|
||||||
)
|
)
|
||||||
) {
|
) {
|
||||||
block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e));
|
block->millimeters = TERN0(HAS_EXTRUDERS, ABS(steps_dist_mm.e));
|
||||||
|
@ -2022,19 +2040,30 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
block->millimeters = SQRT(
|
block->millimeters = SQRT(
|
||||||
#if EITHER(CORE_IS_XY, MARKFORGED_XY)
|
#if EITHER(CORE_IS_XY, MARKFORGED_XY)
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z)
|
sq(steps_dist_mm.head.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.z),
|
||||||
|
+ sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
|
||||||
)
|
)
|
||||||
#elif CORE_IS_XZ
|
#elif CORE_IS_XZ
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z)
|
sq(steps_dist_mm.head.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.head.z),
|
||||||
|
+ sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
|
||||||
)
|
)
|
||||||
#elif CORE_IS_YZ
|
#elif CORE_IS_YZ
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
sq(steps_dist_mm.x), + sq(steps_dist_mm.head.y), + sq(steps_dist_mm.head.z)
|
sq(steps_dist_mm.x) + sq(steps_dist_mm.head.y) + sq(steps_dist_mm.head.z)
|
||||||
|
+ sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
|
||||||
)
|
)
|
||||||
|
#elif ENABLED(FOAMCUTTER_XYUV)
|
||||||
|
// Return the largest distance move from either X/Y or I/J plane
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
_MAX(sq(steps_dist_mm.x) + sq(steps_dist_mm.y), sq(steps_dist_mm.i) + sq(steps_dist_mm.j))
|
||||||
|
#else
|
||||||
|
sq(steps_dist_mm.x) + sq(steps_dist_mm.y)
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z)
|
sq(steps_dist_mm.x), + sq(steps_dist_mm.y), + sq(steps_dist_mm.z),
|
||||||
|
+ sq(steps_dist_mm.i), + sq(steps_dist_mm.j), + sq(steps_dist_mm.k)
|
||||||
)
|
)
|
||||||
#endif
|
#endif
|
||||||
);
|
);
|
||||||
|
@ -2055,7 +2084,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
TERN_(HAS_EXTRUDERS, block->steps.e = esteps);
|
TERN_(HAS_EXTRUDERS, block->steps.e = esteps);
|
||||||
|
|
||||||
block->step_event_count = _MAX(LOGICAL_AXIS_LIST(
|
block->step_event_count = _MAX(LOGICAL_AXIS_LIST(
|
||||||
esteps, block->steps.a, block->steps.b, block->steps.c
|
esteps, block->steps.a, block->steps.b, block->steps.c, block->steps.i, block->steps.j, block->steps.k
|
||||||
));
|
));
|
||||||
|
|
||||||
// Bail if this is a zero-length block
|
// Bail if this is a zero-length block
|
||||||
|
@ -2082,7 +2111,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
if (LINEAR_AXIS_GANG(
|
if (LINEAR_AXIS_GANG(
|
||||||
block->steps.x,
|
block->steps.x,
|
||||||
|| block->steps.y,
|
|| block->steps.y,
|
||||||
|| block->steps.z
|
|| block->steps.z,
|
||||||
|
|| block->steps.i,
|
||||||
|
|| block->steps.j,
|
||||||
|
|| block->steps.k
|
||||||
)) powerManager.power_on();
|
)) powerManager.power_on();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2111,7 +2143,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
if (block->steps.x) ENABLE_AXIS_X(),
|
if (block->steps.x) ENABLE_AXIS_X(),
|
||||||
if (block->steps.y) ENABLE_AXIS_Y(),
|
if (block->steps.y) ENABLE_AXIS_Y(),
|
||||||
if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z()
|
if (TERN(Z_LATE_ENABLE, 0, block->steps.z)) ENABLE_AXIS_Z(),
|
||||||
|
if (block->steps.i) ENABLE_AXIS_I(),
|
||||||
|
if (block->steps.j) ENABLE_AXIS_J(),
|
||||||
|
if (block->steps.k) ENABLE_AXIS_K()
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2301,8 +2336,9 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
const float steps_per_mm = block->step_event_count * inverse_millimeters;
|
const float steps_per_mm = block->step_event_count * inverse_millimeters;
|
||||||
uint32_t accel;
|
uint32_t accel;
|
||||||
if (LINEAR_AXIS_GANG(
|
if (LINEAR_AXIS_GANG(
|
||||||
!block->steps.a, && !block->steps.b, && !block->steps.c
|
!block->steps.a, && !block->steps.b, && !block->steps.c,
|
||||||
)) { // Is this a retract / recover move?
|
&& !block->steps.i, && !block->steps.j, && !block->steps.k)
|
||||||
|
) { // Is this a retract / recover move?
|
||||||
accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2
|
accel = CEIL(settings.retract_acceleration * steps_per_mm); // Convert to: acceleration steps/sec^2
|
||||||
TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover
|
TERN_(LIN_ADVANCE, block->use_advance_lead = false); // No linear advance for simple retract/recover
|
||||||
}
|
}
|
||||||
|
@ -2371,7 +2407,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)),
|
LIMIT_ACCEL_LONG(E_AXIS, E_INDEX_N(extruder)),
|
||||||
LIMIT_ACCEL_LONG(A_AXIS, 0),
|
LIMIT_ACCEL_LONG(A_AXIS, 0),
|
||||||
LIMIT_ACCEL_LONG(B_AXIS, 0),
|
LIMIT_ACCEL_LONG(B_AXIS, 0),
|
||||||
LIMIT_ACCEL_LONG(C_AXIS, 0)
|
LIMIT_ACCEL_LONG(C_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_LONG(I_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_LONG(J_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_LONG(K_AXIS, 0)
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -2379,7 +2418,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)),
|
LIMIT_ACCEL_FLOAT(E_AXIS, E_INDEX_N(extruder)),
|
||||||
LIMIT_ACCEL_FLOAT(A_AXIS, 0),
|
LIMIT_ACCEL_FLOAT(A_AXIS, 0),
|
||||||
LIMIT_ACCEL_FLOAT(B_AXIS, 0),
|
LIMIT_ACCEL_FLOAT(B_AXIS, 0),
|
||||||
LIMIT_ACCEL_FLOAT(C_AXIS, 0)
|
LIMIT_ACCEL_FLOAT(C_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_FLOAT(I_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_FLOAT(J_AXIS, 0),
|
||||||
|
LIMIT_ACCEL_FLOAT(K_AXIS, 0)
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2444,7 +2486,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
#if HAS_DIST_MM_ARG
|
#if HAS_DIST_MM_ARG
|
||||||
cart_dist_mm
|
cart_dist_mm
|
||||||
#else
|
#else
|
||||||
LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z)
|
LOGICAL_AXIS_ARRAY(steps_dist_mm.e, steps_dist_mm.x, steps_dist_mm.y, steps_dist_mm.z, steps_dist_mm.i, steps_dist_mm.j, steps_dist_mm.k)
|
||||||
#endif
|
#endif
|
||||||
;
|
;
|
||||||
|
|
||||||
|
@ -2467,7 +2509,10 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
|
||||||
+ (-prev_unit_vec.e * unit_vec.e),
|
+ (-prev_unit_vec.e * unit_vec.e),
|
||||||
(-prev_unit_vec.x * unit_vec.x),
|
(-prev_unit_vec.x * unit_vec.x),
|
||||||
+ (-prev_unit_vec.y * unit_vec.y),
|
+ (-prev_unit_vec.y * unit_vec.y),
|
||||||
+ (-prev_unit_vec.z * unit_vec.z)
|
+ (-prev_unit_vec.z * unit_vec.z),
|
||||||
|
+ (-prev_unit_vec.i * unit_vec.i),
|
||||||
|
+ (-prev_unit_vec.j * unit_vec.j),
|
||||||
|
+ (-prev_unit_vec.k * unit_vec.k)
|
||||||
);
|
);
|
||||||
|
|
||||||
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
||||||
|
@ -2783,10 +2828,9 @@ void Planner::buffer_sync_block(TERN_(LASER_SYNCHRONOUS_M106_M107, uint8_t sync_
|
||||||
*
|
*
|
||||||
* Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc.
|
* Return 'false' if no segment was queued due to cleaning, cold extrusion, full queue, etc.
|
||||||
*/
|
*/
|
||||||
bool Planner::buffer_segment(
|
bool Planner::buffer_segment(const abce_pos_t &abce
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
|
|
||||||
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
|
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
|
||||||
, const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters/*=0.0*/
|
, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const_float_t millimeters/*=0.0*/
|
||||||
) {
|
) {
|
||||||
|
|
||||||
// If we are cleaning, do not accept queuing of movements
|
// If we are cleaning, do not accept queuing of movements
|
||||||
|
@ -2804,54 +2848,70 @@ bool Planner::buffer_segment(
|
||||||
// Calculate target position in absolute steps
|
// Calculate target position in absolute steps
|
||||||
const abce_long_t target = {
|
const abce_long_t target = {
|
||||||
LOGICAL_AXIS_LIST(
|
LOGICAL_AXIS_LIST(
|
||||||
int32_t(LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])),
|
int32_t(LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(extruder)])),
|
||||||
int32_t(LROUND(a * settings.axis_steps_per_mm[A_AXIS])),
|
int32_t(LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS])),
|
||||||
int32_t(LROUND(b * settings.axis_steps_per_mm[B_AXIS])),
|
int32_t(LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS])),
|
||||||
int32_t(LROUND(c * settings.axis_steps_per_mm[C_AXIS]))
|
int32_t(LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS])),
|
||||||
|
int32_t(LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS])), // FIXME (DerAndere): Multiplication by 4.0 is a work-around for issue with wrong internal steps per mm
|
||||||
|
int32_t(LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS])),
|
||||||
|
int32_t(LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS]))
|
||||||
)
|
)
|
||||||
};
|
};
|
||||||
|
|
||||||
#if HAS_POSITION_FLOAT
|
#if HAS_POSITION_FLOAT
|
||||||
const xyze_pos_t target_float = LOGICAL_AXIS_ARRAY(e, a, b, c);
|
const xyze_pos_t target_float = abce;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
// DRYRUN prevents E moves from taking place
|
// DRYRUN prevents E moves from taking place
|
||||||
if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) {
|
if (DEBUGGING(DRYRUN) || TERN0(CANCEL_OBJECTS, cancelable.skipping)) {
|
||||||
position.e = target.e;
|
position.e = target.e;
|
||||||
TERN_(HAS_POSITION_FLOAT, position_float.e = e);
|
TERN_(HAS_POSITION_FLOAT, position_float.e = abce.e);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* <-- add a slash to enable
|
/* <-- add a slash to enable
|
||||||
SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s);
|
SERIAL_ECHOPAIR(" buffer_segment FR:", fr_mm_s);
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
SERIAL_ECHOPAIR(" A:", a);
|
SERIAL_ECHOPAIR(" A:", abce.a, " (", position.a, "->", target.a, ") B:", abce.b);
|
||||||
SERIAL_ECHOPAIR(" (", position.a);
|
|
||||||
SERIAL_ECHOPAIR("->", target.a);
|
|
||||||
SERIAL_ECHOPAIR(") B:", b);
|
|
||||||
#else
|
#else
|
||||||
SERIAL_ECHOPAIR_P(SP_X_LBL, a);
|
SERIAL_ECHOPAIR_P(SP_X_LBL, abce.a);
|
||||||
SERIAL_ECHOPAIR(" (", position.x);
|
SERIAL_ECHOPAIR(" (", position.x, "->", target.x);
|
||||||
SERIAL_ECHOPAIR("->", target.x);
|
|
||||||
SERIAL_CHAR(')');
|
SERIAL_CHAR(')');
|
||||||
SERIAL_ECHOPAIR_P(SP_Y_LBL, b);
|
SERIAL_ECHOPAIR_P(SP_Y_LBL, abce.b);
|
||||||
#endif
|
#endif
|
||||||
SERIAL_ECHOPAIR(" (", position.y);
|
SERIAL_ECHOPAIR(" (", position.y, "->", target.y);
|
||||||
SERIAL_ECHOPAIR("->", target.y);
|
#if LINEAR_AXES >= ABC
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
SERIAL_ECHOPAIR(") C:", c);
|
SERIAL_ECHOPAIR(") C:", abce.c);
|
||||||
#else
|
#else
|
||||||
SERIAL_CHAR(')');
|
SERIAL_CHAR(')');
|
||||||
SERIAL_ECHOPAIR_P(SP_Z_LBL, c);
|
SERIAL_ECHOPAIR_P(SP_Z_LBL, abce.c);
|
||||||
#endif
|
#endif
|
||||||
SERIAL_ECHOPAIR(" (", position.z);
|
SERIAL_ECHOPAIR(" (", position.z, "->", target.z);
|
||||||
SERIAL_ECHOPAIR("->", target.z);
|
|
||||||
SERIAL_CHAR(')');
|
SERIAL_CHAR(')');
|
||||||
SERIAL_ECHOPAIR_P(SP_E_LBL, e);
|
#endif
|
||||||
SERIAL_ECHOPAIR(" (", position.e);
|
#if LINEAR_AXES >= 4
|
||||||
SERIAL_ECHOPAIR("->", target.e);
|
SERIAL_ECHOPAIR_P(SP_I_LBL, abce.i);
|
||||||
SERIAL_ECHOLNPGM(")");
|
SERIAL_ECHOPAIR(" (", position.i, "->", target.i); // FIXME (DerAndere): Introduce work-around for issue with wrong internal steps per mm and feedrate for I_AXIS
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
SERIAL_ECHOPAIR_P(SP_J_LBL, abce.j);
|
||||||
|
SERIAL_ECHOPAIR(" (", position.j, "->", target.j);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
SERIAL_ECHOPAIR_P(SP_K_LBL, abce.k);
|
||||||
|
SERIAL_ECHOPAIR(" (", position.k, "->", target.k);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
#endif
|
||||||
|
#if HAS_EXTRUDERS
|
||||||
|
SERIAL_ECHOPAIR_P(SP_E_LBL, abce.e);
|
||||||
|
SERIAL_ECHOLNPAIR(" (", position.e, "->", target.e, ")");
|
||||||
|
#else
|
||||||
|
SERIAL_EOL();
|
||||||
|
#endif
|
||||||
//*/
|
//*/
|
||||||
|
|
||||||
// Queue the movement. Return 'false' if the move was not queued.
|
// Queue the movement. Return 'false' if the move was not queued.
|
||||||
|
@ -2874,34 +2934,34 @@ bool Planner::buffer_segment(
|
||||||
* The target is cartesian. It's translated to
|
* The target is cartesian. It's translated to
|
||||||
* delta/scara if needed.
|
* delta/scara if needed.
|
||||||
*
|
*
|
||||||
* rx,ry,rz,e - target position in mm or degrees
|
* cart - target position in mm or degrees
|
||||||
* fr_mm_s - (target) speed of the move (mm/s)
|
* fr_mm_s - (target) speed of the move (mm/s)
|
||||||
* extruder - target extruder
|
* extruder - target extruder
|
||||||
* millimeters - the length of the movement, if known
|
* millimeters - the length of the movement, if known
|
||||||
* inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
|
* inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
|
||||||
*/
|
*/
|
||||||
bool Planner::buffer_line(
|
bool Planner::buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder/*=active_extruder*/, const float millimeters/*=0.0*/
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
|
OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration/*=0.0*/)
|
||||||
, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters
|
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration)
|
|
||||||
) {
|
) {
|
||||||
xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz);
|
xyze_pos_t machine = cart;
|
||||||
TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine));
|
TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine));
|
||||||
|
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
|
|
||||||
#if HAS_JUNCTION_DEVIATION
|
#if HAS_JUNCTION_DEVIATION
|
||||||
const xyze_pos_t cart_dist_mm = {
|
const xyze_pos_t cart_dist_mm = LOGICAL_AXIS_ARRAY(
|
||||||
rx - position_cart.x, ry - position_cart.y,
|
cart.e - position_cart.e,
|
||||||
rz - position_cart.z, e - position_cart.e
|
cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
|
||||||
};
|
cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
|
||||||
|
);
|
||||||
#else
|
#else
|
||||||
const xyz_pos_t cart_dist_mm = { rx - position_cart.x, ry - position_cart.y, rz - position_cart.z };
|
const xyz_pos_t cart_dist_mm = LINEAR_AXIS_ARRAY(
|
||||||
|
cart.x - position_cart.x, cart.y - position_cart.y, cart.z - position_cart.z,
|
||||||
|
cart.i - position_cart.i, cart.j - position_cart.j, cart.j - position_cart.k
|
||||||
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
float mm = millimeters;
|
const float mm = millimeters ?: (cart_dist_mm.x || cart_dist_mm.y) ? cart_dist_mm.magnitude() : TERN0(HAS_Z_AXIS, ABS(cart_dist_mm.z));
|
||||||
if (mm == 0.0)
|
|
||||||
mm = (cart_dist_mm.x != 0.0 || cart_dist_mm.y != 0.0) ? cart_dist_mm.magnitude() : ABS(cart_dist_mm.z);
|
|
||||||
|
|
||||||
// Cartesian XYZ to kinematic ABC, stored in global 'delta'
|
// Cartesian XYZ to kinematic ABC, stored in global 'delta'
|
||||||
inverse_kinematics(machine);
|
inverse_kinematics(machine);
|
||||||
|
@ -2915,16 +2975,11 @@ bool Planner::buffer_line(
|
||||||
#else
|
#else
|
||||||
const feedRate_t feedrate = fr_mm_s;
|
const feedRate_t feedrate = fr_mm_s;
|
||||||
#endif
|
#endif
|
||||||
if (buffer_segment(delta.a, delta.b, delta.c, machine.e
|
delta.e = machine.e;
|
||||||
#if HAS_JUNCTION_DEVIATION
|
if (buffer_segment(delta OPTARG(HAS_DIST_MM_ARG, cart_dist_mm), feedrate, extruder, mm)) {
|
||||||
, cart_dist_mm
|
position_cart = cart;
|
||||||
#endif
|
|
||||||
, feedrate, extruder, mm
|
|
||||||
)) {
|
|
||||||
position_cart.set(rx, ry, rz, e);
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
else
|
|
||||||
return false;
|
return false;
|
||||||
#else
|
#else
|
||||||
return buffer_segment(machine, fr_mm_s, extruder, millimeters);
|
return buffer_segment(machine, fr_mm_s, extruder, millimeters);
|
||||||
|
@ -2991,23 +3046,23 @@ bool Planner::buffer_line(
|
||||||
#endif // DIRECT_STEPPING
|
#endif // DIRECT_STEPPING
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Directly set the planner ABC position (and stepper positions)
|
* Directly set the planner ABCE position (and stepper positions)
|
||||||
* converting mm (or angles for SCARA) into steps.
|
* converting mm (or angles for SCARA) into steps.
|
||||||
*
|
*
|
||||||
* The provided ABC position is in machine units.
|
* The provided ABCE position is in machine units.
|
||||||
*/
|
*/
|
||||||
|
void Planner::set_machine_position_mm(const abce_pos_t &abce) {
|
||||||
void Planner::set_machine_position_mm(
|
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
|
|
||||||
) {
|
|
||||||
TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder);
|
TERN_(DISTINCT_E_FACTORS, last_extruder = active_extruder);
|
||||||
TERN_(HAS_POSITION_FLOAT, position_float.set(LOGICAL_AXIS_LIST(e, a, b, c)));
|
TERN_(HAS_POSITION_FLOAT, position_float = abce);
|
||||||
position.set(
|
position.set(
|
||||||
LOGICAL_AXIS_LIST(
|
LOGICAL_AXIS_LIST(
|
||||||
LROUND(e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]),
|
LROUND(abce.e * settings.axis_steps_per_mm[E_AXIS_N(active_extruder)]),
|
||||||
LROUND(a * settings.axis_steps_per_mm[A_AXIS]),
|
LROUND(abce.a * settings.axis_steps_per_mm[A_AXIS]),
|
||||||
LROUND(b * settings.axis_steps_per_mm[B_AXIS]),
|
LROUND(abce.b * settings.axis_steps_per_mm[B_AXIS]),
|
||||||
LROUND(c * settings.axis_steps_per_mm[C_AXIS])
|
LROUND(abce.c * settings.axis_steps_per_mm[C_AXIS]),
|
||||||
|
LROUND(abce.i * settings.axis_steps_per_mm[I_AXIS]),
|
||||||
|
LROUND(abce.j * settings.axis_steps_per_mm[J_AXIS]),
|
||||||
|
LROUND(abce.k * settings.axis_steps_per_mm[K_AXIS])
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
if (has_blocks_queued()) {
|
if (has_blocks_queued()) {
|
||||||
|
@ -3019,15 +3074,14 @@ void Planner::set_machine_position_mm(
|
||||||
stepper.set_position(position);
|
stepper.set_position(position);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Planner::set_position_mm(
|
void Planner::set_position_mm(const xyze_pos_t &xyze) {
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
|
xyze_pos_t machine = xyze;
|
||||||
) {
|
|
||||||
xyze_pos_t machine = LOGICAL_AXIS_ARRAY(e, rx, ry, rz);
|
|
||||||
TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true));
|
TERN_(HAS_POSITION_MODIFIERS, apply_modifiers(machine, true));
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
position_cart.set(rx, ry, rz, e);
|
position_cart = xyze;
|
||||||
inverse_kinematics(machine);
|
inverse_kinematics(machine);
|
||||||
set_machine_position_mm(delta.a, delta.b, delta.c, machine.e);
|
delta.e = machine.e;
|
||||||
|
set_machine_position_mm(delta);
|
||||||
#else
|
#else
|
||||||
set_machine_position_mm(machine);
|
set_machine_position_mm(machine);
|
||||||
#endif
|
#endif
|
||||||
|
@ -3045,7 +3099,7 @@ void Planner::set_position_mm(
|
||||||
const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]);
|
const float e_new = DIFF_TERN(FWRETRACT, e, fwretract.current_retract[active_extruder]);
|
||||||
position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new);
|
position.e = LROUND(settings.axis_steps_per_mm[axis_index] * e_new);
|
||||||
TERN_(HAS_POSITION_FLOAT, position_float.e = e_new);
|
TERN_(HAS_POSITION_FLOAT, position_float.e = e_new);
|
||||||
TERN_(IS_KINEMATIC, position_cart.e = e);
|
TERN_(IS_KINEMATIC, TERN_(HAS_EXTRUDERS, position_cart.e = e));
|
||||||
|
|
||||||
if (has_blocks_queued())
|
if (has_blocks_queued())
|
||||||
buffer_sync_block();
|
buffer_sync_block();
|
||||||
|
@ -3057,15 +3111,11 @@ void Planner::set_position_mm(
|
||||||
|
|
||||||
// Recalculate the steps/s^2 acceleration rates, based on the mm/s^2
|
// Recalculate the steps/s^2 acceleration rates, based on the mm/s^2
|
||||||
void Planner::reset_acceleration_rates() {
|
void Planner::reset_acceleration_rates() {
|
||||||
#if ENABLED(DISTINCT_E_FACTORS)
|
|
||||||
#define AXIS_CONDITION (i < E_AXIS || i == E_AXIS_N(active_extruder))
|
|
||||||
#else
|
|
||||||
#define AXIS_CONDITION true
|
|
||||||
#endif
|
|
||||||
uint32_t highest_rate = 1;
|
uint32_t highest_rate = 1;
|
||||||
LOOP_DISTINCT_AXES(i) {
|
LOOP_DISTINCT_AXES(i) {
|
||||||
max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i];
|
max_acceleration_steps_per_s2[i] = settings.max_acceleration_mm_per_s2[i] * settings.axis_steps_per_mm[i];
|
||||||
if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
|
if (TERN1(DISTINCT_E_FACTORS, i < E_AXIS || i == E_AXIS_N(active_extruder)))
|
||||||
|
NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
|
||||||
}
|
}
|
||||||
acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL
|
acceleration_long_cutoff = 4294967295UL / highest_rate; // 0xFFFFFFFFUL
|
||||||
TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk());
|
TERN_(HAS_LINEAR_E_JERK, recalculate_max_e_jerk());
|
||||||
|
|
|
@ -76,7 +76,9 @@
|
||||||
// Feedrate for manual moves
|
// Feedrate for manual moves
|
||||||
#ifdef MANUAL_FEEDRATE
|
#ifdef MANUAL_FEEDRATE
|
||||||
constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE,
|
constexpr xyze_feedrate_t _mf = MANUAL_FEEDRATE,
|
||||||
manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f, _mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f);
|
manual_feedrate_mm_s = LOGICAL_AXIS_ARRAY(_mf.e / 60.0f,
|
||||||
|
_mf.x / 60.0f, _mf.y / 60.0f, _mf.z / 60.0f,
|
||||||
|
_mf.i / 60.0f, _mf.j / 60.0f, _mf.k / 60.0f);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if IS_KINEMATIC && HAS_JUNCTION_DEVIATION
|
#if IS_KINEMATIC && HAS_JUNCTION_DEVIATION
|
||||||
|
@ -758,23 +760,11 @@ class Planner {
|
||||||
* extruder - target extruder
|
* extruder - target extruder
|
||||||
* millimeters - the length of the movement, if known
|
* millimeters - the length of the movement, if known
|
||||||
*/
|
*/
|
||||||
static bool buffer_segment(
|
static bool buffer_segment(const abce_pos_t &abce
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
|
|
||||||
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
|
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
|
||||||
, const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0
|
, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const_float_t millimeters=0.0
|
||||||
);
|
);
|
||||||
|
|
||||||
FORCE_INLINE static bool buffer_segment(abce_pos_t &abce
|
|
||||||
OPTARG(HAS_DIST_MM_ARG, const xyze_float_t &cart_dist_mm)
|
|
||||||
, const_feedRate_t fr_mm_s, const uint8_t extruder, const_float_t millimeters=0.0
|
|
||||||
) {
|
|
||||||
return buffer_segment(
|
|
||||||
LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c)
|
|
||||||
OPTARG(HAS_DIST_MM_ARG, cart_dist_mm)
|
|
||||||
, fr_mm_s, extruder, millimeters
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -782,28 +772,16 @@ class Planner {
|
||||||
* The target is cartesian. It's translated to
|
* The target is cartesian. It's translated to
|
||||||
* delta/scara if needed.
|
* delta/scara if needed.
|
||||||
*
|
*
|
||||||
* rx,ry,rz,e - target position in mm or degrees
|
* cart - target position in mm or degrees
|
||||||
* fr_mm_s - (target) speed of the move (mm/s)
|
* fr_mm_s - (target) speed of the move (mm/s)
|
||||||
* extruder - target extruder
|
* extruder - target extruder
|
||||||
* millimeters - the length of the movement, if known
|
* millimeters - the length of the movement, if known
|
||||||
* inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
|
* inv_duration - the reciprocal if the duration of the movement, if known (kinematic only if feeedrate scaling is enabled)
|
||||||
*/
|
*/
|
||||||
static bool buffer_line(
|
static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder=active_extruder, const float millimeters=0.0
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
|
|
||||||
, const feedRate_t &fr_mm_s, const uint8_t extruder, const float millimeters=0.0
|
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0)
|
OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0)
|
||||||
);
|
);
|
||||||
|
|
||||||
FORCE_INLINE static bool buffer_line(const xyze_pos_t &cart, const_feedRate_t fr_mm_s, const uint8_t extruder, const float millimeters=0.0
|
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, const_float_t inv_duration=0.0)
|
|
||||||
) {
|
|
||||||
return buffer_line(
|
|
||||||
LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z)
|
|
||||||
, fr_mm_s, extruder, millimeters
|
|
||||||
OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
#if ENABLED(DIRECT_STEPPING)
|
#if ENABLED(DIRECT_STEPPING)
|
||||||
static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps);
|
static void buffer_page(const page_idx_t page_idx, const uint8_t extruder, const uint16_t num_steps);
|
||||||
#endif
|
#endif
|
||||||
|
@ -821,12 +799,7 @@ class Planner {
|
||||||
*
|
*
|
||||||
* Clears previous speed values.
|
* Clears previous speed values.
|
||||||
*/
|
*/
|
||||||
static void set_position_mm(
|
static void set_position_mm(const xyze_pos_t &xyze);
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t rx, const_float_t ry, const_float_t rz)
|
|
||||||
);
|
|
||||||
FORCE_INLINE static void set_position_mm(const xyze_pos_t &cart) {
|
|
||||||
set_position_mm(LOGICAL_AXIS_LIST(cart.e, cart.x, cart.y, cart.z, cart.i, cart.j, cart.k));
|
|
||||||
}
|
|
||||||
|
|
||||||
#if HAS_EXTRUDERS
|
#if HAS_EXTRUDERS
|
||||||
static void set_e_position_mm(const_float_t e);
|
static void set_e_position_mm(const_float_t e);
|
||||||
|
@ -838,12 +811,7 @@ class Planner {
|
||||||
* The supplied position is in machine space, and no additional
|
* The supplied position is in machine space, and no additional
|
||||||
* conversions are applied.
|
* conversions are applied.
|
||||||
*/
|
*/
|
||||||
static void set_machine_position_mm(
|
static void set_machine_position_mm(const abce_pos_t &abce);
|
||||||
LOGICAL_AXIS_LIST(const_float_t e, const_float_t a, const_float_t b, const_float_t c)
|
|
||||||
);
|
|
||||||
FORCE_INLINE static void set_machine_position_mm(const abce_pos_t &abce) {
|
|
||||||
set_machine_position_mm(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c));
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Get an axis position according to stepper position(s)
|
* Get an axis position according to stepper position(s)
|
||||||
|
@ -854,7 +822,8 @@ class Planner {
|
||||||
static inline abce_pos_t get_axis_positions_mm() {
|
static inline abce_pos_t get_axis_positions_mm() {
|
||||||
const abce_pos_t out = LOGICAL_AXIS_ARRAY(
|
const abce_pos_t out = LOGICAL_AXIS_ARRAY(
|
||||||
get_axis_position_mm(E_AXIS),
|
get_axis_position_mm(E_AXIS),
|
||||||
get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS)
|
get_axis_position_mm(A_AXIS), get_axis_position_mm(B_AXIS), get_axis_position_mm(C_AXIS),
|
||||||
|
get_axis_position_mm(I_AXIS), get_axis_position_mm(J_AXIS), get_axis_position_mm(K_AXIS)
|
||||||
);
|
);
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
|
@ -182,9 +182,13 @@ void cubic_b_spline(
|
||||||
|
|
||||||
// Compute and send new position
|
// Compute and send new position
|
||||||
xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY(
|
xyze_pos_t new_bez = LOGICAL_AXIS_ARRAY(
|
||||||
interp(position.e, target.e, t), // FIXME. These two are wrong, since the parameter t is not linear in the distance.
|
interp(position.e, target.e, t), // FIXME. Wrong, since t is not linear in the distance.
|
||||||
new_pos0, new_pos1,
|
new_pos0,
|
||||||
interp(position.z, target.z, t)
|
new_pos1,
|
||||||
|
interp(position.z, target.z, t), // FIXME. Wrong, since t is not linear in the distance.
|
||||||
|
interp(position.i, target.i, t), // FIXME. Wrong, since t is not linear in the distance.
|
||||||
|
interp(position.j, target.j, t), // FIXME. Wrong, since t is not linear in the distance.
|
||||||
|
interp(position.k, target.k, t) // FIXME. Wrong, since t is not linear in the distance.
|
||||||
);
|
);
|
||||||
apply_motion_limits(new_bez);
|
apply_motion_limits(new_bez);
|
||||||
bez_target = new_bez;
|
bez_target = new_bez;
|
||||||
|
|
|
@ -110,7 +110,7 @@ public:
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
static constexpr xyz_pos_t offset = xyz_pos_t({ 0, 0, 0 }); // See #16767
|
static constexpr xyz_pos_t offset = xyz_pos_t(LINEAR_AXIS_ARRAY(0, 0, 0, 0, 0, 0)); // See #16767
|
||||||
|
|
||||||
static bool set_deployed(const bool) { return false; }
|
static bool set_deployed(const bool) { return false; }
|
||||||
|
|
||||||
|
@ -222,20 +222,20 @@ public:
|
||||||
#define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \
|
#define VALIDATE_PROBE_PT(N) static_assert(Probe::build_time::can_reach(xy_pos_t{PROBE_PT_##N##_X, PROBE_PT_##N##_Y}), \
|
||||||
"PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN");
|
"PROBE_PT_" STRINGIFY(N) "_(X|Y) is unreachable using default NOZZLE_TO_PROBE_OFFSET and PROBING_MARGIN");
|
||||||
VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3);
|
VALIDATE_PROBE_PT(1); VALIDATE_PROBE_PT(2); VALIDATE_PROBE_PT(3);
|
||||||
points[0].set(PROBE_PT_1_X, PROBE_PT_1_Y);
|
points[0] = xy_float_t({ PROBE_PT_1_X, PROBE_PT_1_Y });
|
||||||
points[1].set(PROBE_PT_2_X, PROBE_PT_2_Y);
|
points[1] = xy_float_t({ PROBE_PT_2_X, PROBE_PT_2_Y });
|
||||||
points[2].set(PROBE_PT_3_X, PROBE_PT_3_Y);
|
points[2] = xy_float_t({ PROBE_PT_3_X, PROBE_PT_3_Y });
|
||||||
#else
|
#else
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025,
|
constexpr float SIN0 = 0.0, SIN120 = 0.866025, SIN240 = -0.866025,
|
||||||
COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5;
|
COS0 = 1.0, COS120 = -0.5 , COS240 = -0.5;
|
||||||
points[0].set((X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0);
|
points[0] = xy_float_t({ (X_CENTER) + probe_radius() * COS0, (Y_CENTER) + probe_radius() * SIN0 });
|
||||||
points[1].set((X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120);
|
points[1] = xy_float_t({ (X_CENTER) + probe_radius() * COS120, (Y_CENTER) + probe_radius() * SIN120 });
|
||||||
points[2].set((X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240);
|
points[2] = xy_float_t({ (X_CENTER) + probe_radius() * COS240, (Y_CENTER) + probe_radius() * SIN240 });
|
||||||
#else
|
#else
|
||||||
points[0].set(min_x(), min_y());
|
points[0] = xy_float_t({ min_x(), min_y() });
|
||||||
points[1].set(max_x(), min_y());
|
points[1] = xy_float_t({ max_x(), min_y() });
|
||||||
points[2].set((min_x() + max_x()) / 2, max_y());
|
points[2] = xy_float_t({ (min_x() + max_x()) / 2, max_y() });
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -168,10 +168,14 @@
|
||||||
void M554_report();
|
void M554_report();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stepper_current_t;
|
#define _EN_ITEM(N) , E##N
|
||||||
typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_hybrid_threshold_t;
|
|
||||||
typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t;
|
typedef struct { uint16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stepper_current_t;
|
||||||
typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7; } tmc_stealth_enabled_t;
|
typedef struct { uint32_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_hybrid_threshold_t;
|
||||||
|
typedef struct { int16_t LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4; } tmc_sgt_t;
|
||||||
|
typedef struct { bool LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(E_STEPPERS, _EN_ITEM); } tmc_stealth_enabled_t;
|
||||||
|
|
||||||
|
#undef _EN_ITEM
|
||||||
|
|
||||||
// Limit an index to an array size
|
// Limit an index to an array size
|
||||||
#define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1)
|
#define ALIM(I,ARR) _MIN(I, (signed)COUNT(ARR) - 1)
|
||||||
|
@ -387,7 +391,7 @@ typedef struct SettingsDataStruct {
|
||||||
#ifndef MOTOR_CURRENT_COUNT
|
#ifndef MOTOR_CURRENT_COUNT
|
||||||
#define MOTOR_CURRENT_COUNT LINEAR_AXES
|
#define MOTOR_CURRENT_COUNT LINEAR_AXES
|
||||||
#endif
|
#endif
|
||||||
uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E
|
uint32_t motor_current_setting[MOTOR_CURRENT_COUNT]; // M907 X Z E ...
|
||||||
|
|
||||||
//
|
//
|
||||||
// CNC_COORDINATE_SYSTEMS
|
// CNC_COORDINATE_SYSTEMS
|
||||||
|
@ -654,7 +658,7 @@ void MarlinSettings::postprocess() {
|
||||||
EEPROM_WRITE(dummyf);
|
EEPROM_WRITE(dummyf);
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4);
|
const xyze_pos_t planner_max_jerk = LOGICAL_AXIS_ARRAY(float(DEFAULT_EJERK), 10, 10, 0.4, 0.4, 0.4, 0.4);
|
||||||
EEPROM_WRITE(planner_max_jerk);
|
EEPROM_WRITE(planner_max_jerk);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1087,6 +1091,15 @@ void MarlinSettings::postprocess() {
|
||||||
#if AXIS_IS_TMC(Z)
|
#if AXIS_IS_TMC(Z)
|
||||||
tmc_stepper_current.Z = stepperZ.getMilliamps();
|
tmc_stepper_current.Z = stepperZ.getMilliamps();
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
tmc_stepper_current.I = stepperI.getMilliamps();
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
tmc_stepper_current.J = stepperJ.getMilliamps();
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
tmc_stepper_current.K = stepperK.getMilliamps();
|
||||||
|
#endif
|
||||||
#if AXIS_IS_TMC(X2)
|
#if AXIS_IS_TMC(X2)
|
||||||
tmc_stepper_current.X2 = stepperX2.getMilliamps();
|
tmc_stepper_current.X2 = stepperX2.getMilliamps();
|
||||||
#endif
|
#endif
|
||||||
|
@ -1138,61 +1151,33 @@ void MarlinSettings::postprocess() {
|
||||||
|
|
||||||
#if ENABLED(HYBRID_THRESHOLD)
|
#if ENABLED(HYBRID_THRESHOLD)
|
||||||
tmc_hybrid_threshold_t tmc_hybrid_threshold{0};
|
tmc_hybrid_threshold_t tmc_hybrid_threshold{0};
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, tmc_hybrid_threshold.X = stepperX.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.X = stepperX.get_pwm_thrs();
|
TERN_(Y_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs());
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(I_HAS_STEALTHCHOP, tmc_hybrid_threshold.I = stepperI.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.Y = stepperY.get_pwm_thrs();
|
TERN_(J_HAS_STEALTHCHOP, tmc_hybrid_threshold.J = stepperJ.get_pwm_thrs());
|
||||||
#endif
|
TERN_(K_HAS_STEALTHCHOP, tmc_hybrid_threshold.K = stepperK.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(X2_HAS_STEALTHCHOP, tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.Z = stepperZ.get_pwm_thrs();
|
TERN_(Y2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs());
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(Z3_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.X2 = stepperX2.get_pwm_thrs();
|
TERN_(Z4_HAS_STEALTHCHOP, tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs());
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E1_HAS_STEALTHCHOP, tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.Y2 = stepperY2.get_pwm_thrs();
|
TERN_(E2_HAS_STEALTHCHOP, tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs());
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E4_HAS_STEALTHCHOP, tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.Z2 = stepperZ2.get_pwm_thrs();
|
TERN_(E5_HAS_STEALTHCHOP, tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs());
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
TERN_(E7_HAS_STEALTHCHOP, tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs());
|
||||||
tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
tmc_hybrid_threshold.E1 = stepperE1.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
tmc_hybrid_threshold.E2 = stepperE2.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
tmc_hybrid_threshold.E3 = stepperE3.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
tmc_hybrid_threshold.E4 = stepperE4.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
tmc_hybrid_threshold.E5 = stepperE5.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
tmc_hybrid_threshold.E6 = stepperE6.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
tmc_hybrid_threshold.E7 = stepperE7.get_pwm_thrs();
|
|
||||||
#endif
|
|
||||||
#else
|
#else
|
||||||
|
#define _EN_ITEM(N) , .E##N = 30
|
||||||
const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
|
const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
|
||||||
LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3),
|
LINEAR_AXIS_LIST(.X = 100, .Y = 100, .Z = 3, .I = 3, .J = 3, .K = 3),
|
||||||
.X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3,
|
.X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3
|
||||||
.E0 = 30, .E1 = 30, .E2 = 30, .E3 = 30,
|
REPEAT(EXTRUDERS, _EN_ITEM)
|
||||||
.E4 = 30, .E5 = 30, .E6 = 30, .E7 = 30
|
|
||||||
};
|
};
|
||||||
|
#undef _EN_ITEM
|
||||||
#endif
|
#endif
|
||||||
EEPROM_WRITE(tmc_hybrid_threshold);
|
EEPROM_WRITE(tmc_hybrid_threshold);
|
||||||
}
|
}
|
||||||
|
@ -1203,11 +1188,16 @@ void MarlinSettings::postprocess() {
|
||||||
{
|
{
|
||||||
tmc_sgt_t tmc_sgt{0};
|
tmc_sgt_t tmc_sgt{0};
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold());
|
LINEAR_AXIS_CODE(
|
||||||
|
TERN_(X_SENSORLESS, tmc_sgt.X = stepperX.homing_threshold()),
|
||||||
|
TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold()),
|
||||||
|
TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold()),
|
||||||
|
TERN_(I_SENSORLESS, tmc_sgt.I = stepperI.homing_threshold()),
|
||||||
|
TERN_(J_SENSORLESS, tmc_sgt.J = stepperJ.homing_threshold()),
|
||||||
|
TERN_(K_SENSORLESS, tmc_sgt.K = stepperK.homing_threshold())
|
||||||
|
);
|
||||||
TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold());
|
TERN_(X2_SENSORLESS, tmc_sgt.X2 = stepperX2.homing_threshold());
|
||||||
TERN_(Y_SENSORLESS, tmc_sgt.Y = stepperY.homing_threshold());
|
|
||||||
TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold());
|
TERN_(Y2_SENSORLESS, tmc_sgt.Y2 = stepperY2.homing_threshold());
|
||||||
TERN_(Z_SENSORLESS, tmc_sgt.Z = stepperZ.homing_threshold());
|
|
||||||
TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold());
|
TERN_(Z2_SENSORLESS, tmc_sgt.Z2 = stepperZ2.homing_threshold());
|
||||||
TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold());
|
TERN_(Z3_SENSORLESS, tmc_sgt.Z3 = stepperZ3.homing_threshold());
|
||||||
TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold());
|
TERN_(Z4_SENSORLESS, tmc_sgt.Z4 = stepperZ4.homing_threshold());
|
||||||
|
@ -1222,54 +1212,25 @@ void MarlinSettings::postprocess() {
|
||||||
_FIELD_TEST(tmc_stealth_enabled);
|
_FIELD_TEST(tmc_stealth_enabled);
|
||||||
|
|
||||||
tmc_stealth_enabled_t tmc_stealth_enabled = { false };
|
tmc_stealth_enabled_t tmc_stealth_enabled = { false };
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, tmc_stealth_enabled.X = stepperX.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.X = stepperX.get_stored_stealthChop();
|
TERN_(Y_HAS_STEALTHCHOP, tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(I_HAS_STEALTHCHOP, tmc_stealth_enabled.I = stepperI.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.Y = stepperY.get_stored_stealthChop();
|
TERN_(J_HAS_STEALTHCHOP, tmc_stealth_enabled.J = stepperJ.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(K_HAS_STEALTHCHOP, tmc_stealth_enabled.K = stepperK.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(X2_HAS_STEALTHCHOP, tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.Z = stepperZ.get_stored_stealthChop();
|
TERN_(Y2_HAS_STEALTHCHOP, tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(Z3_HAS_STEALTHCHOP, tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.X2 = stepperX2.get_stored_stealthChop();
|
TERN_(Z4_HAS_STEALTHCHOP, tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E1_HAS_STEALTHCHOP, tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.Y2 = stepperY2.get_stored_stealthChop();
|
TERN_(E2_HAS_STEALTHCHOP, tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E4_HAS_STEALTHCHOP, tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.Z2 = stepperZ2.get_stored_stealthChop();
|
TERN_(E5_HAS_STEALTHCHOP, tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop());
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop());
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
TERN_(E7_HAS_STEALTHCHOP, tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop());
|
||||||
tmc_stealth_enabled.Z3 = stepperZ3.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
tmc_stealth_enabled.Z4 = stepperZ4.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
tmc_stealth_enabled.E0 = stepperE0.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
tmc_stealth_enabled.E1 = stepperE1.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
tmc_stealth_enabled.E2 = stepperE2.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
tmc_stealth_enabled.E3 = stepperE3.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
tmc_stealth_enabled.E4 = stepperE4.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
tmc_stealth_enabled.E5 = stepperE5.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
tmc_stealth_enabled.E6 = stepperE6.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
tmc_stealth_enabled.E7 = stepperE7.get_stored_stealthChop();
|
|
||||||
#endif
|
|
||||||
EEPROM_WRITE(tmc_stealth_enabled);
|
EEPROM_WRITE(tmc_stealth_enabled);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1992,6 +1953,15 @@ void MarlinSettings::postprocess() {
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
SET_CURR(Z4);
|
SET_CURR(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
SET_CURR(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
SET_CURR(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
SET_CURR(K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
SET_CURR(E0);
|
SET_CURR(E0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -2028,54 +1998,25 @@ void MarlinSettings::postprocess() {
|
||||||
|
|
||||||
#if ENABLED(HYBRID_THRESHOLD)
|
#if ENABLED(HYBRID_THRESHOLD)
|
||||||
if (!validating) {
|
if (!validating) {
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, stepperX.set_pwm_thrs(tmc_hybrid_threshold.X));
|
||||||
stepperX.set_pwm_thrs(tmc_hybrid_threshold.X);
|
TERN_(Y_HAS_STEALTHCHOP, stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y));
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(X2_HAS_STEALTHCHOP, stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2));
|
||||||
stepperY.set_pwm_thrs(tmc_hybrid_threshold.Y);
|
TERN_(Y2_HAS_STEALTHCHOP, stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2));
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(Z3_HAS_STEALTHCHOP, stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3));
|
||||||
stepperZ.set_pwm_thrs(tmc_hybrid_threshold.Z);
|
TERN_(Z4_HAS_STEALTHCHOP, stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4));
|
||||||
#endif
|
TERN_(I_HAS_STEALTHCHOP, stepperI.set_pwm_thrs(tmc_hybrid_threshold.I));
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(J_HAS_STEALTHCHOP, stepperJ.set_pwm_thrs(tmc_hybrid_threshold.J));
|
||||||
stepperX2.set_pwm_thrs(tmc_hybrid_threshold.X2);
|
TERN_(K_HAS_STEALTHCHOP, stepperK.set_pwm_thrs(tmc_hybrid_threshold.K));
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E1_HAS_STEALTHCHOP, stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1));
|
||||||
stepperY2.set_pwm_thrs(tmc_hybrid_threshold.Y2);
|
TERN_(E2_HAS_STEALTHCHOP, stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2));
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E4_HAS_STEALTHCHOP, stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4));
|
||||||
stepperZ2.set_pwm_thrs(tmc_hybrid_threshold.Z2);
|
TERN_(E5_HAS_STEALTHCHOP, stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5));
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
TERN_(E7_HAS_STEALTHCHOP, stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7));
|
||||||
stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
stepperE1.set_pwm_thrs(tmc_hybrid_threshold.E1);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
stepperE2.set_pwm_thrs(tmc_hybrid_threshold.E2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
stepperE3.set_pwm_thrs(tmc_hybrid_threshold.E3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
stepperE4.set_pwm_thrs(tmc_hybrid_threshold.E4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
stepperE5.set_pwm_thrs(tmc_hybrid_threshold.E5);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
stepperE6.set_pwm_thrs(tmc_hybrid_threshold.E6);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
stepperE7.set_pwm_thrs(tmc_hybrid_threshold.E7);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -2089,11 +2030,16 @@ void MarlinSettings::postprocess() {
|
||||||
EEPROM_READ(tmc_sgt);
|
EEPROM_READ(tmc_sgt);
|
||||||
#if USE_SENSORLESS
|
#if USE_SENSORLESS
|
||||||
if (!validating) {
|
if (!validating) {
|
||||||
TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X));
|
LINEAR_AXIS_CODE(
|
||||||
|
TERN_(X_SENSORLESS, stepperX.homing_threshold(tmc_sgt.X)),
|
||||||
|
TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y)),
|
||||||
|
TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z)),
|
||||||
|
TERN_(I_SENSORLESS, stepperI.homing_threshold(tmc_sgt.I)),
|
||||||
|
TERN_(J_SENSORLESS, stepperJ.homing_threshold(tmc_sgt.J)),
|
||||||
|
TERN_(K_SENSORLESS, stepperK.homing_threshold(tmc_sgt.K))
|
||||||
|
);
|
||||||
TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2));
|
TERN_(X2_SENSORLESS, stepperX2.homing_threshold(tmc_sgt.X2));
|
||||||
TERN_(Y_SENSORLESS, stepperY.homing_threshold(tmc_sgt.Y));
|
|
||||||
TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2));
|
TERN_(Y2_SENSORLESS, stepperY2.homing_threshold(tmc_sgt.Y2));
|
||||||
TERN_(Z_SENSORLESS, stepperZ.homing_threshold(tmc_sgt.Z));
|
|
||||||
TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2));
|
TERN_(Z2_SENSORLESS, stepperZ2.homing_threshold(tmc_sgt.Z2));
|
||||||
TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3));
|
TERN_(Z3_SENSORLESS, stepperZ3.homing_threshold(tmc_sgt.Z3));
|
||||||
TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4));
|
TERN_(Z4_SENSORLESS, stepperZ4.homing_threshold(tmc_sgt.Z4));
|
||||||
|
@ -2112,54 +2058,25 @@ void MarlinSettings::postprocess() {
|
||||||
|
|
||||||
#define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode();
|
#define SET_STEPPING_MODE(ST) stepper##ST.stored.stealthChop_enabled = tmc_stealth_enabled.ST; stepper##ST.refresh_stepping_mode();
|
||||||
if (!validating) {
|
if (!validating) {
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
TERN_(X_HAS_STEALTHCHOP, SET_STEPPING_MODE(X));
|
||||||
SET_STEPPING_MODE(X);
|
TERN_(Y_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y));
|
||||||
#endif
|
TERN_(Z_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
TERN_(I_HAS_STEALTHCHOP, SET_STEPPING_MODE(I));
|
||||||
SET_STEPPING_MODE(Y);
|
TERN_(J_HAS_STEALTHCHOP, SET_STEPPING_MODE(J));
|
||||||
#endif
|
TERN_(K_HAS_STEALTHCHOP, SET_STEPPING_MODE(K));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
TERN_(X2_HAS_STEALTHCHOP, SET_STEPPING_MODE(X2));
|
||||||
SET_STEPPING_MODE(Z);
|
TERN_(Y2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Y2));
|
||||||
#endif
|
TERN_(Z2_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z2));
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
TERN_(Z3_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z3));
|
||||||
SET_STEPPING_MODE(X2);
|
TERN_(Z4_HAS_STEALTHCHOP, SET_STEPPING_MODE(Z4));
|
||||||
#endif
|
TERN_(E0_HAS_STEALTHCHOP, SET_STEPPING_MODE(E0));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
TERN_(E1_HAS_STEALTHCHOP, SET_STEPPING_MODE(E1));
|
||||||
SET_STEPPING_MODE(Y2);
|
TERN_(E2_HAS_STEALTHCHOP, SET_STEPPING_MODE(E2));
|
||||||
#endif
|
TERN_(E3_HAS_STEALTHCHOP, SET_STEPPING_MODE(E3));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
TERN_(E4_HAS_STEALTHCHOP, SET_STEPPING_MODE(E4));
|
||||||
SET_STEPPING_MODE(Z2);
|
TERN_(E5_HAS_STEALTHCHOP, SET_STEPPING_MODE(E5));
|
||||||
#endif
|
TERN_(E6_HAS_STEALTHCHOP, SET_STEPPING_MODE(E6));
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
TERN_(E7_HAS_STEALTHCHOP, SET_STEPPING_MODE(E7));
|
||||||
SET_STEPPING_MODE(Z3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
|
||||||
SET_STEPPING_MODE(Z4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
|
||||||
SET_STEPPING_MODE(E0);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
|
||||||
SET_STEPPING_MODE(E1);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
|
||||||
SET_STEPPING_MODE(E2);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
SET_STEPPING_MODE(E3);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
SET_STEPPING_MODE(E4);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
SET_STEPPING_MODE(E5);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
SET_STEPPING_MODE(E6);
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
SET_STEPPING_MODE(E7);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -2598,14 +2515,25 @@ void MarlinSettings::reset() {
|
||||||
#ifndef DEFAULT_XJERK
|
#ifndef DEFAULT_XJERK
|
||||||
#define DEFAULT_XJERK 0
|
#define DEFAULT_XJERK 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef DEFAULT_YJERK
|
#if HAS_Y_AXIS && !defined(DEFAULT_YJERK)
|
||||||
#define DEFAULT_YJERK 0
|
#define DEFAULT_YJERK 0
|
||||||
#endif
|
#endif
|
||||||
#ifndef DEFAULT_ZJERK
|
#if HAS_Z_AXIS && !defined(DEFAULT_ZJERK)
|
||||||
#define DEFAULT_ZJERK 0
|
#define DEFAULT_ZJERK 0
|
||||||
#endif
|
#endif
|
||||||
planner.max_jerk.set(LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK));
|
#if LINEAR_AXES >= 4 && !defined(DEFAULT_IJERK)
|
||||||
TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK;);
|
#define DEFAULT_IJERK 0
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && !defined(DEFAULT_JJERK)
|
||||||
|
#define DEFAULT_JJERK 0
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && !defined(DEFAULT_KJERK)
|
||||||
|
#define DEFAULT_KJERK 0
|
||||||
|
#endif
|
||||||
|
planner.max_jerk.set(
|
||||||
|
LINEAR_AXIS_LIST(DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_IJERK, DEFAULT_JJERK, DEFAULT_KJERK)
|
||||||
|
);
|
||||||
|
TERN_(HAS_CLASSIC_E_JERK, planner.max_jerk.e = DEFAULT_EJERK);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_JUNCTION_DEVIATION
|
#if HAS_JUNCTION_DEVIATION
|
||||||
|
@ -2703,11 +2631,11 @@ void MarlinSettings::reset() {
|
||||||
|
|
||||||
#if HAS_BED_PROBE
|
#if HAS_BED_PROBE
|
||||||
constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
|
constexpr float dpo[] = NOZZLE_TO_PROBE_OFFSET;
|
||||||
static_assert(COUNT(dpo) == 3, "NOZZLE_TO_PROBE_OFFSET must contain offsets for X, Y, and Z.");
|
static_assert(COUNT(dpo) == LINEAR_AXES, "NOZZLE_TO_PROBE_OFFSET must contain offsets for each linear axis X, Y, Z....");
|
||||||
#if HAS_PROBE_XY_OFFSET
|
#if HAS_PROBE_XY_OFFSET
|
||||||
LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
|
LOOP_LINEAR_AXES(a) probe.offset[a] = dpo[a];
|
||||||
#else
|
#else
|
||||||
probe.offset.set(0, 0, dpo[Z_AXIS]);
|
probe.offset.set(LINEAR_AXIS_LIST(0, 0, dpo[Z_AXIS], 0, 0, 0));
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -3145,7 +3073,10 @@ void MarlinSettings::reset() {
|
||||||
LIST_N(DOUBLE(LINEAR_AXES),
|
LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
|
PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
|
||||||
SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]),
|
SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]),
|
||||||
SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS])
|
SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]),
|
||||||
|
SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]),
|
||||||
|
SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]),
|
||||||
|
SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS])
|
||||||
)
|
)
|
||||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||||
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
|
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
|
||||||
|
@ -3167,7 +3098,10 @@ void MarlinSettings::reset() {
|
||||||
LIST_N(DOUBLE(LINEAR_AXES),
|
LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
|
PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
|
||||||
SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]),
|
SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]),
|
||||||
SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS])
|
SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]),
|
||||||
|
SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
|
||||||
|
SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
|
||||||
|
SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS])
|
||||||
)
|
)
|
||||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||||
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
|
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
|
||||||
|
@ -3210,9 +3144,14 @@ void MarlinSettings::reset() {
|
||||||
, PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm)
|
, PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm)
|
||||||
#endif
|
#endif
|
||||||
#if HAS_CLASSIC_JERK
|
#if HAS_CLASSIC_JERK
|
||||||
, SP_X_STR, LINEAR_UNIT(planner.max_jerk.x)
|
, LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
, SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y)
|
SP_X_STR, LINEAR_UNIT(planner.max_jerk.x),
|
||||||
, SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z)
|
SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y),
|
||||||
|
SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z),
|
||||||
|
SP_I_STR, LINEAR_UNIT(planner.max_jerk.i),
|
||||||
|
SP_J_STR, LINEAR_UNIT(planner.max_jerk.j),
|
||||||
|
SP_K_STR, LINEAR_UNIT(planner.max_jerk.k)
|
||||||
|
)
|
||||||
#if HAS_CLASSIC_E_JERK
|
#if HAS_CLASSIC_E_JERK
|
||||||
, SP_E_STR, LINEAR_UNIT(planner.max_jerk.e)
|
, SP_E_STR, LINEAR_UNIT(planner.max_jerk.e)
|
||||||
#endif
|
#endif
|
||||||
|
@ -3224,13 +3163,17 @@ void MarlinSettings::reset() {
|
||||||
CONFIG_ECHO_START();
|
CONFIG_ECHO_START();
|
||||||
SERIAL_ECHOLNPAIR_P(
|
SERIAL_ECHOLNPAIR_P(
|
||||||
#if IS_CARTESIAN
|
#if IS_CARTESIAN
|
||||||
PSTR(" M206 X"), LINEAR_UNIT(home_offset.x)
|
LIST_N(LINEAR_AXES,
|
||||||
, SP_Y_STR, LINEAR_UNIT(home_offset.y)
|
PSTR(" M206 X"), LINEAR_UNIT(home_offset.x),
|
||||||
, SP_Z_STR
|
SP_Y_STR, LINEAR_UNIT(home_offset.y),
|
||||||
|
SP_Z_STR, LINEAR_UNIT(home_offset.z),
|
||||||
|
SP_I_STR, LINEAR_UNIT(home_offset.i),
|
||||||
|
SP_J_STR, LINEAR_UNIT(home_offset.j),
|
||||||
|
SP_K_STR, LINEAR_UNIT(home_offset.k)
|
||||||
|
)
|
||||||
#else
|
#else
|
||||||
PSTR(" M206 Z")
|
PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z)
|
||||||
#endif
|
#endif
|
||||||
, LINEAR_UNIT(home_offset.z)
|
|
||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -3582,6 +3525,19 @@ void MarlinSettings::reset() {
|
||||||
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps());
|
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
say_M906(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.getMilliamps());
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
say_M906(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.getMilliamps());
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
say_M906(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.getMilliamps());
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
say_M906(forReplay);
|
say_M906(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
|
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
|
||||||
|
@ -3621,74 +3577,87 @@ void MarlinSettings::reset() {
|
||||||
*/
|
*/
|
||||||
#if ENABLED(HYBRID_THRESHOLD)
|
#if ENABLED(HYBRID_THRESHOLD)
|
||||||
CONFIG_ECHO_HEADING("Hybrid Threshold:");
|
CONFIG_ECHO_HEADING("Hybrid Threshold:");
|
||||||
#if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Z)
|
#if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
#if X_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_X_STR, stepperX.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
#if Y_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
#if Z_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2) || AXIS_HAS_STEALTHCHOP(Y2) || AXIS_HAS_STEALTHCHOP(Z2)
|
#if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOPGM(" I1");
|
SERIAL_ECHOPGM(" I1");
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
#if X2_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_X_STR, stepperX2.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
#if Y2_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_Y_STR, stepperY2.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
#if Z2_HAS_STEALTHCHOP
|
||||||
SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs());
|
SERIAL_ECHOPAIR_P(SP_Z_STR, stepperZ2.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
#if Z3_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
#if Z4_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
#if I_HAS_STEALTHCHOP
|
||||||
|
say_M913(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.get_pwm_thrs());
|
||||||
|
#endif
|
||||||
|
#if J_HAS_STEALTHCHOP
|
||||||
|
say_M913(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.get_pwm_thrs());
|
||||||
|
#endif
|
||||||
|
#if K_HAS_STEALTHCHOP
|
||||||
|
say_M913(forReplay);
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.get_pwm_thrs());
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if E0_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
#if E1_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T1 E", stepperE1.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
#if E2_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T2 E", stepperE2.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
#if E3_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T3 E", stepperE3.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
#if E4_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T4 E", stepperE4.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
#if E5_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T5 E", stepperE5.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
#if E6_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T6 E", stepperE6.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
#if E7_HAS_STEALTHCHOP
|
||||||
say_M913(forReplay);
|
say_M913(forReplay);
|
||||||
SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs());
|
SERIAL_ECHOLNPAIR(" T7 E", stepperE7.get_pwm_thrs());
|
||||||
#endif
|
#endif
|
||||||
|
@ -3743,6 +3712,22 @@ void MarlinSettings::reset() {
|
||||||
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold());
|
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if I_SENSORLESS
|
||||||
|
CONFIG_ECHO_START();
|
||||||
|
say_M914();
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_I_STR, stepperI.homing_threshold());
|
||||||
|
#endif
|
||||||
|
#if J_SENSORLESS
|
||||||
|
CONFIG_ECHO_START();
|
||||||
|
say_M914();
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_J_STR, stepperJ.homing_threshold());
|
||||||
|
#endif
|
||||||
|
#if K_SENSORLESS
|
||||||
|
CONFIG_ECHO_START();
|
||||||
|
say_M914();
|
||||||
|
SERIAL_ECHOLNPAIR_P(SP_K_STR, stepperK.homing_threshold());
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // USE_SENSORLESS
|
#endif // USE_SENSORLESS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -3750,45 +3735,29 @@ void MarlinSettings::reset() {
|
||||||
*/
|
*/
|
||||||
#if HAS_STEALTHCHOP
|
#if HAS_STEALTHCHOP
|
||||||
CONFIG_ECHO_HEADING("Driver stepping mode:");
|
CONFIG_ECHO_HEADING("Driver stepping mode:");
|
||||||
#if AXIS_HAS_STEALTHCHOP(X)
|
const bool chop_x = TERN0(X_HAS_STEALTHCHOP, stepperX.get_stored_stealthChop()),
|
||||||
const bool chop_x = stepperX.get_stored_stealthChop();
|
chop_y = TERN0(Y_HAS_STEALTHCHOP, stepperY.get_stored_stealthChop()),
|
||||||
#else
|
chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()),
|
||||||
constexpr bool chop_x = false;
|
chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()),
|
||||||
#endif
|
chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()),
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y)
|
chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop());
|
||||||
const bool chop_y = stepperY.get_stored_stealthChop();
|
|
||||||
#else
|
|
||||||
constexpr bool chop_y = false;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z)
|
|
||||||
const bool chop_z = stepperZ.get_stored_stealthChop();
|
|
||||||
#else
|
|
||||||
constexpr bool chop_z = false;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (chop_x || chop_y || chop_z) {
|
if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) {
|
||||||
say_M569(forReplay);
|
say_M569(forReplay);
|
||||||
if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR);
|
LINEAR_AXIS_CODE(
|
||||||
if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR);
|
if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR),
|
||||||
if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR);
|
if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR),
|
||||||
|
if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR),
|
||||||
|
if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR),
|
||||||
|
if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR),
|
||||||
|
if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR)
|
||||||
|
);
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(X2)
|
const bool chop_x2 = TERN0(X2_HAS_STEALTHCHOP, stepperX2.get_stored_stealthChop()),
|
||||||
const bool chop_x2 = stepperX2.get_stored_stealthChop();
|
chop_y2 = TERN0(Y2_HAS_STEALTHCHOP, stepperY2.get_stored_stealthChop()),
|
||||||
#else
|
chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop());
|
||||||
constexpr bool chop_x2 = false;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Y2)
|
|
||||||
const bool chop_y2 = stepperY2.get_stored_stealthChop();
|
|
||||||
#else
|
|
||||||
constexpr bool chop_y2 = false;
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z2)
|
|
||||||
const bool chop_z2 = stepperZ2.get_stored_stealthChop();
|
|
||||||
#else
|
|
||||||
constexpr bool chop_z2 = false;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (chop_x2 || chop_y2 || chop_z2) {
|
if (chop_x2 || chop_y2 || chop_z2) {
|
||||||
say_M569(forReplay, PSTR("I1"));
|
say_M569(forReplay, PSTR("I1"));
|
||||||
|
@ -3798,38 +3767,21 @@ void MarlinSettings::reset() {
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z3)
|
if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); }
|
||||||
if (stepperZ3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I2 Z"), true); }
|
if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); }
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(Z4)
|
if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); }
|
||||||
if (stepperZ4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("I3 Z"), true); }
|
if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); }
|
||||||
#endif
|
if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); }
|
||||||
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E0)
|
if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); }
|
||||||
if (stepperE0.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T0 E"), true); }
|
if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); }
|
||||||
#endif
|
if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); }
|
||||||
#if AXIS_HAS_STEALTHCHOP(E1)
|
if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); }
|
||||||
if (stepperE1.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T1 E"), true); }
|
if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); }
|
||||||
#endif
|
if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); }
|
||||||
#if AXIS_HAS_STEALTHCHOP(E2)
|
if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); }
|
||||||
if (stepperE2.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T2 E"), true); }
|
if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); }
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E3)
|
|
||||||
if (stepperE3.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T3 E"), true); }
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E4)
|
|
||||||
if (stepperE4.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T4 E"), true); }
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E5)
|
|
||||||
if (stepperE5.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T5 E"), true); }
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E6)
|
|
||||||
if (stepperE6.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T6 E"), true); }
|
|
||||||
#endif
|
|
||||||
#if AXIS_HAS_STEALTHCHOP(E7)
|
|
||||||
if (stepperE7.get_stored_stealthChop()) { say_M569(forReplay, PSTR("T7 E"), true); }
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // HAS_STEALTHCHOP
|
#endif // HAS_STEALTHCHOP
|
||||||
|
|
||||||
|
@ -3859,7 +3811,7 @@ void MarlinSettings::reset() {
|
||||||
);
|
);
|
||||||
#elif HAS_MOTOR_CURRENT_SPI
|
#elif HAS_MOTOR_CURRENT_SPI
|
||||||
SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values:
|
SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values:
|
||||||
LOOP_LOGICAL_AXES(q) { // X Y Z E (map to X Y Z E0 by default)
|
LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default)
|
||||||
SERIAL_CHAR(' ', axis_codes[q]);
|
SERIAL_CHAR(' ', axis_codes[q]);
|
||||||
SERIAL_ECHO(stepper.motor_current_setting[q]);
|
SERIAL_ECHO(stepper.motor_current_setting[q]);
|
||||||
}
|
}
|
||||||
|
@ -3869,7 +3821,7 @@ void MarlinSettings::reset() {
|
||||||
#elif ENABLED(HAS_MOTOR_CURRENT_I2C) // i2c-based has any number of values
|
#elif ENABLED(HAS_MOTOR_CURRENT_I2C) // i2c-based has any number of values
|
||||||
// Values sent over i2c are not stored.
|
// Values sent over i2c are not stored.
|
||||||
// Indexes map directly to drivers, not axes.
|
// Indexes map directly to drivers, not axes.
|
||||||
#elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z E
|
#elif ENABLED(HAS_MOTOR_CURRENT_DAC) // DAC-based has 4 values, for X Y Z (I J K) E
|
||||||
// Values sent over i2c are not stored. Uses indirect mapping.
|
// Values sent over i2c are not stored. Uses indirect mapping.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -3901,7 +3853,10 @@ void MarlinSettings::reset() {
|
||||||
, LIST_N(DOUBLE(LINEAR_AXES),
|
, LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x),
|
SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x),
|
||||||
SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y),
|
SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y),
|
||||||
SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z)
|
SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z),
|
||||||
|
SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i),
|
||||||
|
SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j),
|
||||||
|
SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k)
|
||||||
)
|
)
|
||||||
#ifdef BACKLASH_SMOOTHING_MM
|
#ifdef BACKLASH_SMOOTHING_MM
|
||||||
, PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm)
|
, PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm)
|
||||||
|
|
|
@ -378,7 +378,7 @@ xyze_int8_t Stepper::count_direction{0};
|
||||||
#else
|
#else
|
||||||
#define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0)
|
#define Y_APPLY_STEP(v,Q) do{ Y_STEP_WRITE(v); Y2_STEP_WRITE(v); }while(0)
|
||||||
#endif
|
#endif
|
||||||
#else
|
#elif HAS_Y_AXIS
|
||||||
#define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v)
|
#define Y_APPLY_DIR(v,Q) Y_DIR_WRITE(v)
|
||||||
#define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
|
#define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
|
||||||
#endif
|
#endif
|
||||||
|
@ -415,11 +415,24 @@ xyze_int8_t Stepper::count_direction{0};
|
||||||
#else
|
#else
|
||||||
#define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0)
|
#define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); }while(0)
|
||||||
#endif
|
#endif
|
||||||
#else
|
#elif HAS_Z_AXIS
|
||||||
#define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
|
#define Z_APPLY_DIR(v,Q) Z_DIR_WRITE(v)
|
||||||
#define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
|
#define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define I_APPLY_DIR(v,Q) I_DIR_WRITE(v)
|
||||||
|
#define I_APPLY_STEP(v,Q) I_STEP_WRITE(v)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define J_APPLY_DIR(v,Q) J_DIR_WRITE(v)
|
||||||
|
#define J_APPLY_STEP(v,Q) J_STEP_WRITE(v)
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define K_APPLY_DIR(v,Q) K_DIR_WRITE(v)
|
||||||
|
#define K_APPLY_STEP(v,Q) K_STEP_WRITE(v)
|
||||||
|
#endif
|
||||||
|
|
||||||
#if DISABLED(MIXING_EXTRUDER)
|
#if DISABLED(MIXING_EXTRUDER)
|
||||||
#define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v)
|
#define E_APPLY_STEP(v,Q) E_STEP_WRITE(stepper_extruder, v)
|
||||||
#endif
|
#endif
|
||||||
|
@ -486,6 +499,18 @@ void Stepper::set_directions() {
|
||||||
SET_STEP_DIR(Z); // C
|
SET_STEP_DIR(Z); // C
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_I_DIR
|
||||||
|
SET_STEP_DIR(I); // I
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_J_DIR
|
||||||
|
SET_STEP_DIR(J); // J
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_K_DIR
|
||||||
|
SET_STEP_DIR(K); // K
|
||||||
|
#endif
|
||||||
|
|
||||||
#if DISABLED(LIN_ADVANCE)
|
#if DISABLED(LIN_ADVANCE)
|
||||||
#if ENABLED(MIXING_EXTRUDER)
|
#if ENABLED(MIXING_EXTRUDER)
|
||||||
// Because this is valid for the whole block we don't know
|
// Because this is valid for the whole block we don't know
|
||||||
|
@ -1584,7 +1609,7 @@ void Stepper::pulse_phase_isr() {
|
||||||
const bool is_page = IS_PAGE(current_block);
|
const bool is_page = IS_PAGE(current_block);
|
||||||
|
|
||||||
#if ENABLED(DIRECT_STEPPING)
|
#if ENABLED(DIRECT_STEPPING)
|
||||||
|
// TODO (DerAndere): Add support for LINEAR_AXES >= 4
|
||||||
if (is_page) {
|
if (is_page) {
|
||||||
|
|
||||||
#if STEPPER_PAGE_FORMAT == SP_4x4D_128
|
#if STEPPER_PAGE_FORMAT == SP_4x4D_128
|
||||||
|
@ -1700,6 +1725,15 @@ void Stepper::pulse_phase_isr() {
|
||||||
#if HAS_Z_STEP
|
#if HAS_Z_STEP
|
||||||
PULSE_PREP(Z);
|
PULSE_PREP(Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_STEP
|
||||||
|
PULSE_PREP(I);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_STEP
|
||||||
|
PULSE_PREP(J);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_STEP
|
||||||
|
PULSE_PREP(K);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
|
#if EITHER(LIN_ADVANCE, MIXING_EXTRUDER)
|
||||||
delta_error.e += advance_dividend.e;
|
delta_error.e += advance_dividend.e;
|
||||||
|
@ -1735,6 +1769,15 @@ void Stepper::pulse_phase_isr() {
|
||||||
#if HAS_Z_STEP
|
#if HAS_Z_STEP
|
||||||
PULSE_START(Z);
|
PULSE_START(Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_STEP
|
||||||
|
PULSE_START(I);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_STEP
|
||||||
|
PULSE_START(J);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_STEP
|
||||||
|
PULSE_START(K);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if DISABLED(LIN_ADVANCE)
|
#if DISABLED(LIN_ADVANCE)
|
||||||
#if ENABLED(MIXING_EXTRUDER)
|
#if ENABLED(MIXING_EXTRUDER)
|
||||||
|
@ -1764,6 +1807,15 @@ void Stepper::pulse_phase_isr() {
|
||||||
#if HAS_Z_STEP
|
#if HAS_Z_STEP
|
||||||
PULSE_STOP(Z);
|
PULSE_STOP(Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_STEP
|
||||||
|
PULSE_STOP(I);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_STEP
|
||||||
|
PULSE_STOP(J);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_STEP
|
||||||
|
PULSE_STOP(K);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if DISABLED(LIN_ADVANCE)
|
#if DISABLED(LIN_ADVANCE)
|
||||||
#if ENABLED(MIXING_EXTRUDER)
|
#if ENABLED(MIXING_EXTRUDER)
|
||||||
|
@ -1798,6 +1850,7 @@ uint32_t Stepper::block_phase_isr() {
|
||||||
// If current block is finished, reset pointer and finalize state
|
// If current block is finished, reset pointer and finalize state
|
||||||
if (step_events_completed >= step_event_count) {
|
if (step_events_completed >= step_event_count) {
|
||||||
#if ENABLED(DIRECT_STEPPING)
|
#if ENABLED(DIRECT_STEPPING)
|
||||||
|
// TODO (DerAndere): Add support for LINEAR_AXES >= 4
|
||||||
#if STEPPER_PAGE_FORMAT == SP_4x4D_128
|
#if STEPPER_PAGE_FORMAT == SP_4x4D_128
|
||||||
#define PAGE_SEGMENT_UPDATE_POS(AXIS) \
|
#define PAGE_SEGMENT_UPDATE_POS(AXIS) \
|
||||||
count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7;
|
count_position[_AXIS(AXIS)] += page_step_state.bd[_AXIS(AXIS)] - 128 * 7;
|
||||||
|
@ -2106,7 +2159,10 @@ uint32_t Stepper::block_phase_isr() {
|
||||||
LINEAR_AXIS_CODE(
|
LINEAR_AXIS_CODE(
|
||||||
if (X_MOVE_TEST) SBI(axis_bits, A_AXIS),
|
if (X_MOVE_TEST) SBI(axis_bits, A_AXIS),
|
||||||
if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS),
|
if (Y_MOVE_TEST) SBI(axis_bits, B_AXIS),
|
||||||
if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS)
|
if (Z_MOVE_TEST) SBI(axis_bits, C_AXIS),
|
||||||
|
if (current_block->steps.i) SBI(axis_bits, I_AXIS),
|
||||||
|
if (current_block->steps.j) SBI(axis_bits, J_AXIS),
|
||||||
|
if (current_block->steps.k) SBI(axis_bits, K_AXIS)
|
||||||
);
|
);
|
||||||
//if (current_block->steps.e) SBI(axis_bits, E_AXIS);
|
//if (current_block->steps.e) SBI(axis_bits, E_AXIS);
|
||||||
//if (current_block->steps.a) SBI(axis_bits, X_HEAD);
|
//if (current_block->steps.a) SBI(axis_bits, X_HEAD);
|
||||||
|
@ -2441,6 +2497,15 @@ void Stepper::init() {
|
||||||
Z4_DIR_INIT();
|
Z4_DIR_INIT();
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_DIR
|
||||||
|
I_DIR_INIT();
|
||||||
|
#endif
|
||||||
|
#if HAS_J_DIR
|
||||||
|
J_DIR_INIT();
|
||||||
|
#endif
|
||||||
|
#if HAS_K_DIR
|
||||||
|
K_DIR_INIT();
|
||||||
|
#endif
|
||||||
#if HAS_E0_DIR
|
#if HAS_E0_DIR
|
||||||
E0_DIR_INIT();
|
E0_DIR_INIT();
|
||||||
#endif
|
#endif
|
||||||
|
@ -2499,6 +2564,18 @@ void Stepper::init() {
|
||||||
if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
|
if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_ENABLE
|
||||||
|
I_ENABLE_INIT();
|
||||||
|
if (!I_ENABLE_ON) I_ENABLE_WRITE(HIGH);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_ENABLE
|
||||||
|
J_ENABLE_INIT();
|
||||||
|
if (!J_ENABLE_ON) J_ENABLE_WRITE(HIGH);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_ENABLE
|
||||||
|
K_ENABLE_INIT();
|
||||||
|
if (!K_ENABLE_ON) K_ENABLE_WRITE(HIGH);
|
||||||
|
#endif
|
||||||
#if HAS_E0_ENABLE
|
#if HAS_E0_ENABLE
|
||||||
E0_ENABLE_INIT();
|
E0_ENABLE_INIT();
|
||||||
if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
|
if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH);
|
||||||
|
@ -2575,6 +2652,15 @@ void Stepper::init() {
|
||||||
#endif
|
#endif
|
||||||
AXIS_INIT(Z, Z);
|
AXIS_INIT(Z, Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_STEP
|
||||||
|
AXIS_INIT(I, I);
|
||||||
|
#endif
|
||||||
|
#if HAS_J_STEP
|
||||||
|
AXIS_INIT(J, J);
|
||||||
|
#endif
|
||||||
|
#if HAS_K_STEP
|
||||||
|
AXIS_INIT(K, K);
|
||||||
|
#endif
|
||||||
|
|
||||||
#if E_STEPPERS && HAS_E0_STEP
|
#if E_STEPPERS && HAS_E0_STEP
|
||||||
E_AXIS_INIT(0);
|
E_AXIS_INIT(0);
|
||||||
|
@ -2612,7 +2698,10 @@ void Stepper::init() {
|
||||||
LINEAR_AXIS_GANG(
|
LINEAR_AXIS_GANG(
|
||||||
| TERN0(INVERT_X_DIR, _BV(X_AXIS)),
|
| TERN0(INVERT_X_DIR, _BV(X_AXIS)),
|
||||||
| TERN0(INVERT_Y_DIR, _BV(Y_AXIS)),
|
| TERN0(INVERT_Y_DIR, _BV(Y_AXIS)),
|
||||||
| TERN0(INVERT_Z_DIR, _BV(Z_AXIS))
|
| TERN0(INVERT_Z_DIR, _BV(Z_AXIS)),
|
||||||
|
| TERN0(INVERT_I_DIR, _BV(I_AXIS)),
|
||||||
|
| TERN0(INVERT_J_DIR, _BV(J_AXIS)),
|
||||||
|
| TERN0(INVERT_K_DIR, _BV(K_AXIS))
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
|
@ -2625,32 +2714,32 @@ void Stepper::init() {
|
||||||
/**
|
/**
|
||||||
* Set the stepper positions directly in steps
|
* Set the stepper positions directly in steps
|
||||||
*
|
*
|
||||||
* The input is based on the typical per-axis XYZ steps.
|
* The input is based on the typical per-axis XYZE steps.
|
||||||
* For CORE machines XYZ needs to be translated to ABC.
|
* For CORE machines XYZ needs to be translated to ABC.
|
||||||
*
|
*
|
||||||
* This allows get_axis_position_mm to correctly
|
* This allows get_axis_position_mm to correctly
|
||||||
* derive the current XYZ position later on.
|
* derive the current XYZE position later on.
|
||||||
*/
|
*/
|
||||||
void Stepper::_set_position(
|
void Stepper::_set_position(const abce_long_t &spos) {
|
||||||
LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
|
#if EITHER(IS_CORE, MARKFORGED_XY)
|
||||||
) {
|
|
||||||
#if CORE_IS_XY
|
#if CORE_IS_XY
|
||||||
// corexy positioning
|
// corexy positioning
|
||||||
// these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html
|
// these equations follow the form of the dA and dB equations on https://www.corexy.com/theory.html
|
||||||
count_position.set(a + b, CORESIGN(a - b), c);
|
count_position.set(spos.a + spos.b, CORESIGN(spos.a - spos.b), spos.c);
|
||||||
#elif CORE_IS_XZ
|
#elif CORE_IS_XZ
|
||||||
// corexz planning
|
// corexz planning
|
||||||
count_position.set(a + c, b, CORESIGN(a - c));
|
count_position.set(spos.a + spos.c, spos.b, CORESIGN(spos.a - spos.c));
|
||||||
#elif CORE_IS_YZ
|
#elif CORE_IS_YZ
|
||||||
// coreyz planning
|
// coreyz planning
|
||||||
count_position.set(a, b + c, CORESIGN(b - c));
|
count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c));
|
||||||
#elif ENABLED(MARKFORGED_XY)
|
#elif ENABLED(MARKFORGED_XY)
|
||||||
count_position.set(a - b, b, c);
|
count_position.set(spos.a - spos.b, spos.b, spos.c);
|
||||||
|
#endif
|
||||||
|
TERN_(HAS_EXTRUDERS, count_position.e = spos.e);
|
||||||
#else
|
#else
|
||||||
// default non-h-bot planning
|
// default non-h-bot planning
|
||||||
count_position.set(LINEAR_AXIS_LIST(a, b, c));
|
count_position = spos;
|
||||||
#endif
|
#endif
|
||||||
TERN_(HAS_EXTRUDERS, count_position.e = e);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -2673,13 +2762,10 @@ int32_t Stepper::position(const AxisEnum axis) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the current position in steps
|
// Set the current position in steps
|
||||||
//TODO: Test for LINEAR_AXES >= 4
|
void Stepper::set_position(const xyze_long_t &spos) {
|
||||||
void Stepper::set_position(
|
|
||||||
LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
|
|
||||||
) {
|
|
||||||
planner.synchronize();
|
planner.synchronize();
|
||||||
const bool was_enabled = suspend();
|
const bool was_enabled = suspend();
|
||||||
_set_position(LOGICAL_AXIS_LIST(e, a, b, c));
|
_set_position(spos);
|
||||||
if (was_enabled) wake_up();
|
if (was_enabled) wake_up();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2747,18 +2833,24 @@ int32_t Stepper::triggered_position(const AxisEnum axis) {
|
||||||
return v;
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA)
|
||||||
|
#define USES_ABC 1
|
||||||
|
#endif
|
||||||
|
#if ANY(USES_ABC, MARKFORGED_XY, IS_SCARA)
|
||||||
|
#define USES_AB 1
|
||||||
|
#endif
|
||||||
|
|
||||||
void Stepper::report_a_position(const xyz_long_t &pos) {
|
void Stepper::report_a_position(const xyz_long_t &pos) {
|
||||||
#if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, DELTA, IS_SCARA)
|
SERIAL_ECHOLNPAIR_P(
|
||||||
SERIAL_ECHOPAIR(STR_COUNT_A, pos.x, " B:", pos.y);
|
LIST_N(DOUBLE(LINEAR_AXES),
|
||||||
#else
|
TERN(USES_AB, PSTR(STR_COUNT_A), PSTR(STR_COUNT_X)), pos.x,
|
||||||
SERIAL_ECHOPAIR_P(PSTR(STR_COUNT_X), pos.x, SP_Y_LBL, pos.y);
|
TERN(USES_AB, PSTR("B:"), SP_Y_LBL), pos.y,
|
||||||
#endif
|
TERN(USES_ABC, PSTR("C:"), SP_Z_LBL), pos.z,
|
||||||
#if ANY(CORE_IS_XZ, CORE_IS_YZ, DELTA)
|
SP_I_LBL, pos.i,
|
||||||
SERIAL_ECHOPAIR(" C:", pos.z);
|
SP_J_LBL, pos.j,
|
||||||
#elif LINEAR_AXES >= 3
|
SP_K_LBL, pos.k
|
||||||
SERIAL_ECHOPAIR_P(SP_Z_LBL, pos.z);
|
)
|
||||||
#endif
|
);
|
||||||
SERIAL_EOL();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Stepper::report_positions() {
|
void Stepper::report_positions() {
|
||||||
|
@ -2866,9 +2958,7 @@ void Stepper::report_positions() {
|
||||||
// No other ISR should ever interrupt this!
|
// No other ISR should ever interrupt this!
|
||||||
void Stepper::do_babystep(const AxisEnum axis, const bool direction) {
|
void Stepper::do_babystep(const AxisEnum axis, const bool direction) {
|
||||||
|
|
||||||
#if DISABLED(INTEGRATED_BABYSTEPPING)
|
IF_DISABLED(INTEGRATED_BABYSTEPPING, cli());
|
||||||
cli();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
switch (axis) {
|
switch (axis) {
|
||||||
|
|
||||||
|
@ -2912,35 +3002,90 @@ void Stepper::report_positions() {
|
||||||
ENABLE_AXIS_X();
|
ENABLE_AXIS_X();
|
||||||
ENABLE_AXIS_Y();
|
ENABLE_AXIS_Y();
|
||||||
ENABLE_AXIS_Z();
|
ENABLE_AXIS_Z();
|
||||||
|
ENABLE_AXIS_I();
|
||||||
|
ENABLE_AXIS_J();
|
||||||
|
ENABLE_AXIS_K();
|
||||||
|
|
||||||
DIR_WAIT_BEFORE();
|
DIR_WAIT_BEFORE();
|
||||||
|
|
||||||
const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ());
|
const xyz_byte_t old_dir = LINEAR_AXIS_ARRAY(X_DIR_READ(), Y_DIR_READ(), Z_DIR_READ(), I_DIR_READ(), J_DIR_READ(), K_DIR_READ());
|
||||||
|
|
||||||
X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
|
X_DIR_WRITE(INVERT_X_DIR ^ z_direction);
|
||||||
|
#ifdef Y_DIR_WRITE
|
||||||
Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
|
Y_DIR_WRITE(INVERT_Y_DIR ^ z_direction);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_DIR_WRITE
|
||||||
Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
|
Z_DIR_WRITE(INVERT_Z_DIR ^ z_direction);
|
||||||
|
#endif
|
||||||
|
#ifdef I_DIR_WRITE
|
||||||
|
I_DIR_WRITE(INVERT_I_DIR ^ z_direction);
|
||||||
|
#endif
|
||||||
|
#ifdef J_DIR_WRITE
|
||||||
|
J_DIR_WRITE(INVERT_J_DIR ^ z_direction);
|
||||||
|
#endif
|
||||||
|
#ifdef K_DIR_WRITE
|
||||||
|
K_DIR_WRITE(INVERT_K_DIR ^ z_direction);
|
||||||
|
#endif
|
||||||
|
|
||||||
DIR_WAIT_AFTER();
|
DIR_WAIT_AFTER();
|
||||||
|
|
||||||
_SAVE_START();
|
_SAVE_START();
|
||||||
|
|
||||||
X_STEP_WRITE(!INVERT_X_STEP_PIN);
|
X_STEP_WRITE(!INVERT_X_STEP_PIN);
|
||||||
|
#ifdef Y_STEP_WRITE
|
||||||
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
|
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_STEP_WRITE
|
||||||
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
|
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef I_STEP_WRITE
|
||||||
|
I_STEP_WRITE(!INVERT_I_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef J_STEP_WRITE
|
||||||
|
J_STEP_WRITE(!INVERT_J_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef K_STEP_WRITE
|
||||||
|
K_STEP_WRITE(!INVERT_K_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
_PULSE_WAIT();
|
_PULSE_WAIT();
|
||||||
|
|
||||||
X_STEP_WRITE(INVERT_X_STEP_PIN);
|
X_STEP_WRITE(INVERT_X_STEP_PIN);
|
||||||
|
#ifdef Y_STEP_WRITE
|
||||||
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
|
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_STEP_WRITE
|
||||||
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
|
Z_STEP_WRITE(INVERT_Z_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef I_STEP_WRITE
|
||||||
|
I_STEP_WRITE(INVERT_I_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef J_STEP_WRITE
|
||||||
|
J_STEP_WRITE(INVERT_J_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
#ifdef K_STEP_WRITE
|
||||||
|
K_STEP_WRITE(INVERT_K_STEP_PIN);
|
||||||
|
#endif
|
||||||
|
|
||||||
// Restore direction bits
|
// Restore direction bits
|
||||||
EXTRA_DIR_WAIT_BEFORE();
|
EXTRA_DIR_WAIT_BEFORE();
|
||||||
|
|
||||||
X_DIR_WRITE(old_dir.x);
|
X_DIR_WRITE(old_dir.x);
|
||||||
|
#ifdef Y_DIR_WRITE
|
||||||
Y_DIR_WRITE(old_dir.y);
|
Y_DIR_WRITE(old_dir.y);
|
||||||
|
#endif
|
||||||
|
#ifdef Z_DIR_WRITE
|
||||||
Z_DIR_WRITE(old_dir.z);
|
Z_DIR_WRITE(old_dir.z);
|
||||||
|
#endif
|
||||||
|
#ifdef I_DIR_WRITE
|
||||||
|
I_DIR_WRITE(old_dir.i);
|
||||||
|
#endif
|
||||||
|
#ifdef J_DIR_WRITE
|
||||||
|
J_DIR_WRITE(old_dir.j);
|
||||||
|
#endif
|
||||||
|
#ifdef K_DIR_WRITE
|
||||||
|
K_DIR_WRITE(old_dir.k);
|
||||||
|
#endif
|
||||||
|
|
||||||
EXTRA_DIR_WAIT_AFTER();
|
EXTRA_DIR_WAIT_AFTER();
|
||||||
|
|
||||||
|
@ -2948,12 +3093,20 @@ void Stepper::report_positions() {
|
||||||
|
|
||||||
} break;
|
} break;
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
case I_AXIS: BABYSTEP_AXIS(I, 0, direction); break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
case J_AXIS: BABYSTEP_AXIS(J, 0, direction); break;
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
case K_AXIS: BABYSTEP_AXIS(K, 0, direction); break;
|
||||||
|
#endif
|
||||||
|
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if DISABLED(INTEGRATED_BABYSTEPPING)
|
IF_DISABLED(INTEGRATED_BABYSTEPPING, sei());
|
||||||
sei();
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // BABYSTEPPING
|
#endif // BABYSTEPPING
|
||||||
|
@ -3288,6 +3441,15 @@ void Stepper::report_positions() {
|
||||||
#if HAS_E7_MS_PINS
|
#if HAS_E7_MS_PINS
|
||||||
case 10: WRITE(E7_MS1_PIN, ms1); break;
|
case 10: WRITE(E7_MS1_PIN, ms1); break;
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MICROSTEPS
|
||||||
|
case 11: WRITE(I_MS1_PIN, ms1); break
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MICROSTEPS
|
||||||
|
case 12: WRITE(J_MS1_PIN, ms1); break
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MICROSTEPS
|
||||||
|
case 13: WRITE(K_MS1_PIN, ms1); break
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
if (ms2 >= 0) switch (driver) {
|
if (ms2 >= 0) switch (driver) {
|
||||||
#if HAS_X_MS_PINS || HAS_X2_MS_PINS
|
#if HAS_X_MS_PINS || HAS_X2_MS_PINS
|
||||||
|
@ -3350,6 +3512,15 @@ void Stepper::report_positions() {
|
||||||
#if HAS_E7_MS_PINS
|
#if HAS_E7_MS_PINS
|
||||||
case 10: WRITE(E7_MS2_PIN, ms2); break;
|
case 10: WRITE(E7_MS2_PIN, ms2); break;
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_M_PINS
|
||||||
|
case 11: WRITE(I_MS2_PIN, ms2); break
|
||||||
|
#endif
|
||||||
|
#if HAS_J_M_PINS
|
||||||
|
case 12: WRITE(J_MS2_PIN, ms2); break
|
||||||
|
#endif
|
||||||
|
#if HAS_K_M_PINS
|
||||||
|
case 13: WRITE(K_MS2_PIN, ms2); break
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
if (ms3 >= 0) switch (driver) {
|
if (ms3 >= 0) switch (driver) {
|
||||||
#if HAS_X_MS_PINS || HAS_X2_MS_PINS
|
#if HAS_X_MS_PINS || HAS_X2_MS_PINS
|
||||||
|
@ -3468,6 +3639,24 @@ void Stepper::report_positions() {
|
||||||
PIN_CHAR(Z_MS3);
|
PIN_CHAR(Z_MS3);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if HAS_I_MS_PINS
|
||||||
|
MS_LINE(I);
|
||||||
|
#if PIN_EXISTS(I_MS3)
|
||||||
|
PIN_CHAR(I_MS3);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if HAS_J_MS_PINS
|
||||||
|
MS_LINE(J);
|
||||||
|
#if PIN_EXISTS(J_MS3)
|
||||||
|
PIN_CHAR(J_MS3);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if HAS_K_MS_PINS
|
||||||
|
MS_LINE(K);
|
||||||
|
#if PIN_EXISTS(K_MS3)
|
||||||
|
PIN_CHAR(K_MS3);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#if HAS_E0_MS_PINS
|
#if HAS_E0_MS_PINS
|
||||||
MS_LINE(E0);
|
MS_LINE(E0);
|
||||||
#if PIN_EXISTS(E0_MS3)
|
#if PIN_EXISTS(E0_MS3)
|
||||||
|
|
|
@ -133,27 +133,6 @@
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Add time for each stepper
|
|
||||||
#if HAS_X_STEP
|
|
||||||
#define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
|
||||||
#else
|
|
||||||
#define ISR_X_STEPPER_CYCLES 0UL
|
|
||||||
#endif
|
|
||||||
#if HAS_Y_STEP
|
|
||||||
#define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
|
||||||
#else
|
|
||||||
#define ISR_START_Y_STEPPER_CYCLES 0UL
|
|
||||||
#define ISR_Y_STEPPER_CYCLES 0UL
|
|
||||||
#endif
|
|
||||||
#if HAS_Z_STEP
|
|
||||||
#define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
|
||||||
#else
|
|
||||||
#define ISR_Z_STEPPER_CYCLES 0UL
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// E is always interpolated, even for mixing extruders
|
|
||||||
#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
|
||||||
|
|
||||||
// If linear advance is disabled, the loop also handles them
|
// If linear advance is disabled, the loop also handles them
|
||||||
#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER)
|
#if DISABLED(LIN_ADVANCE) && ENABLED(MIXING_EXTRUDER)
|
||||||
#define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
|
#define ISR_MIXING_STEPPER_CYCLES ((MIXING_STEPPERS) * (ISR_STEPPER_CYCLES))
|
||||||
|
@ -161,8 +140,31 @@
|
||||||
#define ISR_MIXING_STEPPER_CYCLES 0UL
|
#define ISR_MIXING_STEPPER_CYCLES 0UL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add time for each stepper
|
||||||
|
#if HAS_X_STEP
|
||||||
|
#define ISR_X_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_Y_STEP
|
||||||
|
#define ISR_Y_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_Z_STEP
|
||||||
|
#define ISR_Z_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_I_STEP
|
||||||
|
#define ISR_I_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_J_STEP
|
||||||
|
#define ISR_J_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_K_STEP
|
||||||
|
#define ISR_K_STEPPER_CYCLES ISR_STEPPER_CYCLES
|
||||||
|
#endif
|
||||||
|
#if HAS_EXTRUDERS
|
||||||
|
#define ISR_E_STEPPER_CYCLES ISR_STEPPER_CYCLES // E is always interpolated, even for mixing extruders
|
||||||
|
#endif
|
||||||
|
|
||||||
// And the total minimum loop time, not including the base
|
// And the total minimum loop time, not including the base
|
||||||
#define MIN_ISR_LOOP_CYCLES (ISR_X_STEPPER_CYCLES + ISR_Y_STEPPER_CYCLES + ISR_Z_STEPPER_CYCLES + ISR_E_STEPPER_CYCLES + ISR_MIXING_STEPPER_CYCLES)
|
#define MIN_ISR_LOOP_CYCLES (ISR_MIXING_STEPPER_CYCLES LOGICAL_AXIS_GANG(+ ISR_E_STEPPER_CYCLES, + ISR_X_STEPPER_CYCLES, + ISR_Y_STEPPER_CYCLES, + ISR_Z_STEPPER_CYCLES, + ISR_I_STEPPER_CYCLES, + ISR_J_STEPPER_CYCLES, + ISR_K_STEPPER_CYCLES))
|
||||||
|
|
||||||
// Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
|
// Calculate the minimum MPU cycles needed per pulse to enforce, limited to the max stepper rate
|
||||||
#define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
|
#define _MIN_STEPPER_PULSE_CYCLES(N) _MAX(uint32_t((F_CPU) / (MAXIMUM_STEPPER_RATE)), ((F_CPU) / 500000UL) * (N))
|
||||||
|
@ -433,12 +435,7 @@ class Stepper {
|
||||||
static int32_t position(const AxisEnum axis);
|
static int32_t position(const AxisEnum axis);
|
||||||
|
|
||||||
// Set the current position in steps
|
// Set the current position in steps
|
||||||
static void set_position(
|
static void set_position(const xyze_long_t &spos);
|
||||||
LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
|
|
||||||
);
|
|
||||||
static inline void set_position(const xyze_long_t &abce) {
|
|
||||||
set_position(LOGICAL_AXIS_LIST(abce.e, abce.a, abce.b, abce.c));
|
|
||||||
}
|
|
||||||
static void set_axis_position(const AxisEnum a, const int32_t &v);
|
static void set_axis_position(const AxisEnum a, const int32_t &v);
|
||||||
|
|
||||||
// Report the positions of the steppers, in steps
|
// Report the positions of the steppers, in steps
|
||||||
|
@ -534,12 +531,7 @@ class Stepper {
|
||||||
private:
|
private:
|
||||||
|
|
||||||
// Set the current position in steps
|
// Set the current position in steps
|
||||||
static void _set_position(
|
static void _set_position(const abce_long_t &spos);
|
||||||
LOGICAL_AXIS_LIST(const int32_t &e, const int32_t &a, const int32_t &b, const int32_t &c)
|
|
||||||
);
|
|
||||||
FORCE_INLINE static void _set_position(const abce_long_t &spos) {
|
|
||||||
_set_position(LOGICAL_AXIS_LIST(spos.e, spos.a, spos.b, spos.c));
|
|
||||||
}
|
|
||||||
|
|
||||||
FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) {
|
FORCE_INLINE static uint32_t calc_timer_interval(uint32_t step_rate, uint8_t *loops) {
|
||||||
uint32_t timer;
|
uint32_t timer;
|
||||||
|
|
|
@ -55,6 +55,15 @@
|
||||||
#if AXIS_IS_L64XX(Z4)
|
#if AXIS_IS_L64XX(Z4)
|
||||||
L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
|
L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
L64XX_CLASS(I) stepperI(L6470_CHAIN_SS_PIN);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
L64XX_CLASS(J) stepperJ(L6470_CHAIN_SS_PIN);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
L64XX_CLASS(K) stepperK(L6470_CHAIN_SS_PIN);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
|
L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
@ -199,6 +208,15 @@ void L64XX_Marlin::init_to_defaults() {
|
||||||
#if AXIS_IS_L64XX(Z4)
|
#if AXIS_IS_L64XX(Z4)
|
||||||
L6470_INIT_CHIP(Z4);
|
L6470_INIT_CHIP(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
L6470_INIT_CHIP(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
L6470_INIT_CHIP(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
L6470_INIT_CHIP(K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
L6470_INIT_CHIP(E0);
|
L6470_INIT_CHIP(E0);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -206,6 +206,66 @@
|
||||||
#define DISABLE_STEPPER_Z4() stepperZ4.free()
|
#define DISABLE_STEPPER_Z4() stepperZ4.free()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// I Stepper
|
||||||
|
#if AXIS_IS_L64XX(I)
|
||||||
|
extern L64XX_CLASS(I) stepperI;
|
||||||
|
#define I_ENABLE_INIT() NOOP
|
||||||
|
#define I_ENABLE_WRITE(STATE) (STATE ? stepperI.hardStop() : stepperI.free())
|
||||||
|
#define I_ENABLE_READ() (stepperI.getStatus() & STATUS_HIZ)
|
||||||
|
#if AXIS_DRIVER_TYPE_I(L6474)
|
||||||
|
#define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN)
|
||||||
|
#define I_DIR_WRITE(STATE) L6474_DIR_WRITE(I, STATE)
|
||||||
|
#define I_DIR_READ() READ(I_DIR_PIN)
|
||||||
|
#else
|
||||||
|
#define I_DIR_INIT() NOOP
|
||||||
|
#define I_DIR_WRITE(STATE) L64XX_DIR_WRITE(I, STATE)
|
||||||
|
#define I_DIR_READ() (stepper##I.getStatus() & STATUS_DIR);
|
||||||
|
#if AXIS_DRIVER_TYPE_I(L6470)
|
||||||
|
#define DISABLE_STEPPER_I() stepperI.free()
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// J Stepper
|
||||||
|
#if AXIS_IS_L64XX(J)
|
||||||
|
extern L64XX_CLASS(J) stepperJ;
|
||||||
|
#define J_ENABLE_INIT() NOOP
|
||||||
|
#define J_ENABLE_WRITE(STATE) (STATE ? stepperJ.hardStop() : stepperJ.free())
|
||||||
|
#define J_ENABLE_READ() (stepperJ.getStatus() & STATUS_HIZ)
|
||||||
|
#if AXIS_DRIVER_TYPE_J(L6474)
|
||||||
|
#define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN)
|
||||||
|
#define J_DIR_WRITE(STATE) L6474_DIR_WRITE(J, STATE)
|
||||||
|
#define J_DIR_READ() READ(J_DIR_PIN)
|
||||||
|
#else
|
||||||
|
#define J_DIR_INIT() NOOP
|
||||||
|
#define J_DIR_WRITE(STATE) L64XX_DIR_WRITE(J, STATE)
|
||||||
|
#define J_DIR_READ() (stepper##J.getStatus() & STATUS_DIR);
|
||||||
|
#if AXIS_DRIVER_TYPE_J(L6470)
|
||||||
|
#define DISABLE_STEPPER_J() stepperJ.free()
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// K Stepper
|
||||||
|
#if AXIS_IS_L64XX(K)
|
||||||
|
extern L64XX_CLASS(K) stepperK;
|
||||||
|
#define K_ENABLE_INIT() NOOP
|
||||||
|
#define K_ENABLE_WRITE(STATE) (STATE ? stepperK.hardStop() : stepperK.free())
|
||||||
|
#define K_ENABLE_READ() (stepperK.getStatus() & STATUS_HIZ)
|
||||||
|
#if AXIS_DRIVER_TYPE_K(L6474)
|
||||||
|
#define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN)
|
||||||
|
#define K_DIR_WRITE(STATE) L6474_DIR_WRITE(K, STATE)
|
||||||
|
#define K_DIR_READ() READ(K_DIR_PIN)
|
||||||
|
#else
|
||||||
|
#define K_DIR_INIT() NOOP
|
||||||
|
#define K_DIR_WRITE(STATE) L64XX_DIR_WRITE(K, STATE)
|
||||||
|
#define K_DIR_READ() (stepper##K.getStatus() & STATUS_DIR);
|
||||||
|
#if AXIS_DRIVER_TYPE_K(L6470)
|
||||||
|
#define DISABLE_STEPPER_K() stepperK.free()
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
// E0 Stepper
|
// E0 Stepper
|
||||||
#if AXIS_IS_L64XX(E0)
|
#if AXIS_IS_L64XX(E0)
|
||||||
extern L64XX_CLASS(E0) stepperE0;
|
extern L64XX_CLASS(E0) stepperE0;
|
||||||
|
|
|
@ -60,6 +60,15 @@
|
||||||
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
|
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
|
||||||
_TMC26X_DEFINE(Z4);
|
_TMC26X_DEFINE(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_I(TMC26X)
|
||||||
|
_TMC26X_DEFINE(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_J(TMC26X)
|
||||||
|
_TMC26X_DEFINE(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_K(TMC26X)
|
||||||
|
_TMC26X_DEFINE(K);
|
||||||
|
#endif
|
||||||
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
||||||
_TMC26X_DEFINE(E0);
|
_TMC26X_DEFINE(E0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -115,6 +124,15 @@ void tmc26x_init_to_defaults() {
|
||||||
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
|
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
|
||||||
_TMC26X_INIT(Z4);
|
_TMC26X_INIT(Z4);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_I(TMC26X)
|
||||||
|
_TMC26X_INIT(I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_J(TMC26X)
|
||||||
|
_TMC26X_INIT(J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_DRIVER_TYPE_K(TMC26X)
|
||||||
|
_TMC26X_INIT(K);
|
||||||
|
#endif
|
||||||
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
||||||
_TMC26X_INIT(E0);
|
_TMC26X_INIT(E0);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -99,6 +99,30 @@ void tmc26x_init_to_defaults();
|
||||||
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
|
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// I Stepper
|
||||||
|
#if HAS_I_ENABLE && AXIS_DRIVER_TYPE_I(TMC26X)
|
||||||
|
extern TMC26XStepper stepperI;
|
||||||
|
#define I_ENABLE_INIT() NOOP
|
||||||
|
#define I_ENABLE_WRITE(STATE) stepperI.setEnabled(STATE)
|
||||||
|
#define I_ENABLE_READ() stepperI.isEnabled()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// J Stepper
|
||||||
|
#if HAS_J_ENABLE && AXIS_DRIVER_TYPE_J(TMC26X)
|
||||||
|
extern TMC26XStepper stepperJ;
|
||||||
|
#define J_ENABLE_INIT() NOOP
|
||||||
|
#define J_ENABLE_WRITE(STATE) stepperJ.setEnabled(STATE)
|
||||||
|
#define J_ENABLE_READ() stepperJ.isEnabled()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// K Stepper
|
||||||
|
#if HAS_K_ENABLE && AXIS_DRIVER_TYPE_K(TMC26X)
|
||||||
|
extern TMC26XStepper stepperK;
|
||||||
|
#define K_ENABLE_INIT() NOOP
|
||||||
|
#define K_ENABLE_WRITE(STATE) stepperK.setEnabled(STATE)
|
||||||
|
#define K_ENABLE_READ() stepperK.isEnabled()
|
||||||
|
#endif
|
||||||
|
|
||||||
// E0 Stepper
|
// E0 Stepper
|
||||||
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
#if AXIS_DRIVER_TYPE_E0(TMC26X)
|
||||||
extern TMC26XStepper stepperE0;
|
extern TMC26XStepper stepperE0;
|
||||||
|
|
|
@ -37,9 +37,7 @@ void restore_stepper_drivers() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void reset_stepper_drivers() {
|
void reset_stepper_drivers() {
|
||||||
#if HAS_DRIVER(TMC26X)
|
TERN_(HAS_TMC26X, tmc26x_init_to_defaults());
|
||||||
tmc26x_init_to_defaults();
|
|
||||||
#endif
|
|
||||||
TERN_(HAS_L64XX, L64xxManager.init_to_defaults());
|
TERN_(HAS_L64XX, L64xxManager.init_to_defaults());
|
||||||
TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers());
|
TERN_(HAS_TRINAMIC_CONFIG, reset_trinamic_drivers());
|
||||||
}
|
}
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include "L64xx.h"
|
#include "L64xx.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_DRIVER(TMC26X)
|
#if HAS_TMC26X
|
||||||
#include "TMC26X.h"
|
#include "TMC26X.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -65,38 +65,42 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
||||||
#define X_STEP_READ() bool(READ(X_STEP_PIN))
|
#define X_STEP_READ() bool(READ(X_STEP_PIN))
|
||||||
|
|
||||||
// Y Stepper
|
// Y Stepper
|
||||||
#ifndef Y_ENABLE_INIT
|
#if HAS_Y_AXIS
|
||||||
|
#ifndef Y_ENABLE_INIT
|
||||||
#define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN)
|
#define Y_ENABLE_INIT() SET_OUTPUT(Y_ENABLE_PIN)
|
||||||
#define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE)
|
#define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE)
|
||||||
#define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN))
|
#define Y_ENABLE_READ() bool(READ(Y_ENABLE_PIN))
|
||||||
#endif
|
#endif
|
||||||
#ifndef Y_DIR_INIT
|
#ifndef Y_DIR_INIT
|
||||||
#define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
|
#define Y_DIR_INIT() SET_OUTPUT(Y_DIR_PIN)
|
||||||
#define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE)
|
#define Y_DIR_WRITE(STATE) WRITE(Y_DIR_PIN,STATE)
|
||||||
#define Y_DIR_READ() bool(READ(Y_DIR_PIN))
|
#define Y_DIR_READ() bool(READ(Y_DIR_PIN))
|
||||||
#endif
|
#endif
|
||||||
#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN)
|
#define Y_STEP_INIT() SET_OUTPUT(Y_STEP_PIN)
|
||||||
#ifndef Y_STEP_WRITE
|
#ifndef Y_STEP_WRITE
|
||||||
#define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE)
|
#define Y_STEP_WRITE(STATE) WRITE(Y_STEP_PIN,STATE)
|
||||||
|
#endif
|
||||||
|
#define Y_STEP_READ() bool(READ(Y_STEP_PIN))
|
||||||
#endif
|
#endif
|
||||||
#define Y_STEP_READ() bool(READ(Y_STEP_PIN))
|
|
||||||
|
|
||||||
// Z Stepper
|
// Z Stepper
|
||||||
#ifndef Z_ENABLE_INIT
|
#if HAS_Z_AXIS
|
||||||
|
#ifndef Z_ENABLE_INIT
|
||||||
#define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN)
|
#define Z_ENABLE_INIT() SET_OUTPUT(Z_ENABLE_PIN)
|
||||||
#define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE)
|
#define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE)
|
||||||
#define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN))
|
#define Z_ENABLE_READ() bool(READ(Z_ENABLE_PIN))
|
||||||
#endif
|
#endif
|
||||||
#ifndef Z_DIR_INIT
|
#ifndef Z_DIR_INIT
|
||||||
#define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
|
#define Z_DIR_INIT() SET_OUTPUT(Z_DIR_PIN)
|
||||||
#define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE)
|
#define Z_DIR_WRITE(STATE) WRITE(Z_DIR_PIN,STATE)
|
||||||
#define Z_DIR_READ() bool(READ(Z_DIR_PIN))
|
#define Z_DIR_READ() bool(READ(Z_DIR_PIN))
|
||||||
#endif
|
#endif
|
||||||
#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN)
|
#define Z_STEP_INIT() SET_OUTPUT(Z_STEP_PIN)
|
||||||
#ifndef Z_STEP_WRITE
|
#ifndef Z_STEP_WRITE
|
||||||
#define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE)
|
#define Z_STEP_WRITE(STATE) WRITE(Z_STEP_PIN,STATE)
|
||||||
|
#endif
|
||||||
|
#define Z_STEP_READ() bool(READ(Z_STEP_PIN))
|
||||||
#endif
|
#endif
|
||||||
#define Z_STEP_READ() bool(READ(Z_STEP_PIN))
|
|
||||||
|
|
||||||
// X2 Stepper
|
// X2 Stepper
|
||||||
#if HAS_X2_ENABLE
|
#if HAS_X2_ENABLE
|
||||||
|
@ -201,6 +205,63 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
||||||
#define Z4_DIR_WRITE(STATE) NOOP
|
#define Z4_DIR_WRITE(STATE) NOOP
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// I Stepper
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#ifndef I_ENABLE_INIT
|
||||||
|
#define I_ENABLE_INIT() SET_OUTPUT(I_ENABLE_PIN)
|
||||||
|
#define I_ENABLE_WRITE(STATE) WRITE(I_ENABLE_PIN,STATE)
|
||||||
|
#define I_ENABLE_READ() bool(READ(I_ENABLE_PIN))
|
||||||
|
#endif
|
||||||
|
#ifndef I_DIR_INIT
|
||||||
|
#define I_DIR_INIT() SET_OUTPUT(I_DIR_PIN)
|
||||||
|
#define I_DIR_WRITE(STATE) WRITE(I_DIR_PIN,STATE)
|
||||||
|
#define I_DIR_READ() bool(READ(I_DIR_PIN))
|
||||||
|
#endif
|
||||||
|
#define I_STEP_INIT() SET_OUTPUT(I_STEP_PIN)
|
||||||
|
#ifndef I_STEP_WRITE
|
||||||
|
#define I_STEP_WRITE(STATE) WRITE(I_STEP_PIN,STATE)
|
||||||
|
#endif
|
||||||
|
#define I_STEP_READ() bool(READ(I_STEP_PIN))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// J Stepper
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#ifndef J_ENABLE_INIT
|
||||||
|
#define J_ENABLE_INIT() SET_OUTPUT(J_ENABLE_PIN)
|
||||||
|
#define J_ENABLE_WRITE(STATE) WRITE(J_ENABLE_PIN,STATE)
|
||||||
|
#define J_ENABLE_READ() bool(READ(J_ENABLE_PIN))
|
||||||
|
#endif
|
||||||
|
#ifndef J_DIR_INIT
|
||||||
|
#define J_DIR_INIT() SET_OUTPUT(J_DIR_PIN)
|
||||||
|
#define J_DIR_WRITE(STATE) WRITE(J_DIR_PIN,STATE)
|
||||||
|
#define J_DIR_READ() bool(READ(J_DIR_PIN))
|
||||||
|
#endif
|
||||||
|
#define J_STEP_INIT() SET_OUTPUT(J_STEP_PIN)
|
||||||
|
#ifndef J_STEP_WRITE
|
||||||
|
#define J_STEP_WRITE(STATE) WRITE(J_STEP_PIN,STATE)
|
||||||
|
#endif
|
||||||
|
#define J_STEP_READ() bool(READ(J_STEP_PIN))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// K Stepper
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#ifndef K_ENABLE_INIT
|
||||||
|
#define K_ENABLE_INIT() SET_OUTPUT(K_ENABLE_PIN)
|
||||||
|
#define K_ENABLE_WRITE(STATE) WRITE(K_ENABLE_PIN,STATE)
|
||||||
|
#define K_ENABLE_READ() bool(READ(K_ENABLE_PIN))
|
||||||
|
#endif
|
||||||
|
#ifndef K_DIR_INIT
|
||||||
|
#define K_DIR_INIT() SET_OUTPUT(K_DIR_PIN)
|
||||||
|
#define K_DIR_WRITE(STATE) WRITE(K_DIR_PIN,STATE)
|
||||||
|
#define K_DIR_READ() bool(READ(K_DIR_PIN))
|
||||||
|
#endif
|
||||||
|
#define K_STEP_INIT() SET_OUTPUT(K_STEP_PIN)
|
||||||
|
#ifndef K_STEP_WRITE
|
||||||
|
#define K_STEP_WRITE(STATE) WRITE(K_STEP_PIN,STATE)
|
||||||
|
#endif
|
||||||
|
#define K_STEP_READ() bool(READ(K_STEP_PIN))
|
||||||
|
#endif
|
||||||
|
|
||||||
// E0 Stepper
|
// E0 Stepper
|
||||||
#ifndef E0_ENABLE_INIT
|
#ifndef E0_ENABLE_INIT
|
||||||
#define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
|
#define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
|
||||||
|
@ -720,6 +781,51 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef ENABLE_STEPPER_I
|
||||||
|
#if HAS_I_ENABLE
|
||||||
|
#define ENABLE_STEPPER_I() I_ENABLE_WRITE( I_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define ENABLE_STEPPER_I() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_STEPPER_I
|
||||||
|
#if HAS_I_ENABLE
|
||||||
|
#define DISABLE_STEPPER_I() I_ENABLE_WRITE(!I_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define DISABLE_STEPPER_I() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ENABLE_STEPPER_J
|
||||||
|
#if HAS_J_ENABLE
|
||||||
|
#define ENABLE_STEPPER_J() J_ENABLE_WRITE( J_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define ENABLE_STEPPER_J() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_STEPPER_J
|
||||||
|
#if HAS_J_ENABLE
|
||||||
|
#define DISABLE_STEPPER_J() J_ENABLE_WRITE(!J_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define DISABLE_STEPPER_J() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ENABLE_STEPPER_K
|
||||||
|
#if HAS_K_ENABLE
|
||||||
|
#define ENABLE_STEPPER_K() K_ENABLE_WRITE( K_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define ENABLE_STEPPER_K() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_STEPPER_K
|
||||||
|
#if HAS_K_ENABLE
|
||||||
|
#define DISABLE_STEPPER_K() K_ENABLE_WRITE(!K_ENABLE_ON)
|
||||||
|
#else
|
||||||
|
#define DISABLE_STEPPER_K() NOOP
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef ENABLE_STEPPER_E0
|
#ifndef ENABLE_STEPPER_E0
|
||||||
#if HAS_E0_ENABLE
|
#if HAS_E0_ENABLE
|
||||||
#define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON)
|
#define ENABLE_STEPPER_E0() E0_ENABLE_WRITE( E_ENABLE_ON)
|
||||||
|
@ -857,10 +963,22 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
||||||
|
|
||||||
#define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); }
|
#define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); }
|
||||||
#define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); }
|
#define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); }
|
||||||
#define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); }
|
|
||||||
#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); }
|
#if HAS_Y_AXIS
|
||||||
#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); }
|
#define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); }
|
||||||
#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); }
|
#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); }
|
||||||
|
#else
|
||||||
|
#define ENABLE_AXIS_Y() NOOP
|
||||||
|
#define DISABLE_AXIS_Y() NOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_AXIS
|
||||||
|
#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); }
|
||||||
|
#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); }
|
||||||
|
#else
|
||||||
|
#define ENABLE_AXIS_Z() NOOP
|
||||||
|
#define DISABLE_AXIS_Z() NOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef Z_IDLE_HEIGHT
|
#ifdef Z_IDLE_HEIGHT
|
||||||
#define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0)
|
#define Z_RESET() do{ current_position.z = Z_IDLE_HEIGHT; sync_plan_position(); }while(0)
|
||||||
|
@ -868,6 +986,28 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
|
||||||
#define Z_RESET()
|
#define Z_RESET()
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#define ENABLE_AXIS_I() if (SHOULD_ENABLE(i)) { ENABLE_STEPPER_I(); AFTER_CHANGE(i, true); }
|
||||||
|
#define DISABLE_AXIS_I() if (SHOULD_DISABLE(i)) { DISABLE_STEPPER_I(); AFTER_CHANGE(i, false); set_axis_untrusted(I_AXIS); }
|
||||||
|
#else
|
||||||
|
#define ENABLE_AXIS_I() NOOP
|
||||||
|
#define DISABLE_AXIS_I() NOOP
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#define ENABLE_AXIS_J() if (SHOULD_ENABLE(j)) { ENABLE_STEPPER_J(); AFTER_CHANGE(j, true); }
|
||||||
|
#define DISABLE_AXIS_J() if (SHOULD_DISABLE(j)) { DISABLE_STEPPER_J(); AFTER_CHANGE(j, false); set_axis_untrusted(J_AXIS); }
|
||||||
|
#else
|
||||||
|
#define ENABLE_AXIS_J() NOOP
|
||||||
|
#define DISABLE_AXIS_J() NOOP
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#define ENABLE_AXIS_K() if (SHOULD_ENABLE(k)) { ENABLE_STEPPER_K(); AFTER_CHANGE(k, true); }
|
||||||
|
#define DISABLE_AXIS_K() if (SHOULD_DISABLE(k)) { DISABLE_STEPPER_K(); AFTER_CHANGE(k, false); set_axis_untrusted(K_AXIS); }
|
||||||
|
#else
|
||||||
|
#define ENABLE_AXIS_K() NOOP
|
||||||
|
#define DISABLE_AXIS_K() NOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Extruder steppers enable / disable macros
|
// Extruder steppers enable / disable macros
|
||||||
//
|
//
|
||||||
|
|
|
@ -36,7 +36,7 @@
|
||||||
#include <SPI.h>
|
#include <SPI.h>
|
||||||
|
|
||||||
enum StealthIndex : uint8_t {
|
enum StealthIndex : uint8_t {
|
||||||
LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z)
|
LOGICAL_AXIS_LIST(STEALTH_AXIS_E, STEALTH_AXIS_X, STEALTH_AXIS_Y, STEALTH_AXIS_Z, STEALTH_AXIS_I, STEALTH_AXIS_J, STEALTH_AXIS_K)
|
||||||
};
|
};
|
||||||
#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE)
|
#define TMC_INIT(ST, STEALTH_INDEX) tmc_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, stealthchop_by_axis[STEALTH_INDEX], chopper_timing_##ST, ST##_INTERPOLATE)
|
||||||
|
|
||||||
|
@ -97,6 +97,15 @@ enum StealthIndex : uint8_t {
|
||||||
#if AXIS_HAS_SPI(Z4)
|
#if AXIS_HAS_SPI(Z4)
|
||||||
TMC_SPI_DEFINE(Z4, Z);
|
TMC_SPI_DEFINE(Z4, Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(I)
|
||||||
|
TMC_SPI_DEFINE(I, I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(J)
|
||||||
|
TMC_SPI_DEFINE(J, J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SPI(K)
|
||||||
|
TMC_SPI_DEFINE(K, K);
|
||||||
|
#endif
|
||||||
#if AXIS_HAS_SPI(E0)
|
#if AXIS_HAS_SPI(E0)
|
||||||
TMC_SPI_DEFINE_E(0);
|
TMC_SPI_DEFINE_E(0);
|
||||||
#endif
|
#endif
|
||||||
|
@ -329,6 +338,34 @@ enum StealthIndex : uint8_t {
|
||||||
#define Z4_HAS_SW_SERIAL 1
|
#define Z4_HAS_SW_SERIAL 1
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_HAS_UART(I)
|
||||||
|
#ifdef I_HARDWARE_SERIAL
|
||||||
|
TMC_UART_DEFINE(HW, I, I);
|
||||||
|
#define I_HAS_HW_SERIAL 1
|
||||||
|
#else
|
||||||
|
TMC_UART_DEFINE(SW, I, I);
|
||||||
|
#define I_HAS_SW_SERIAL 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_UART(J)
|
||||||
|
#ifdef J_HARDWARE_SERIAL
|
||||||
|
TMC_UART_DEFINE(HW, J, J);
|
||||||
|
#define J_HAS_HW_SERIAL 1
|
||||||
|
#else
|
||||||
|
TMC_UART_DEFINE(SW, J, J);
|
||||||
|
#define J_HAS_SW_SERIAL 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_UART(K)
|
||||||
|
#ifdef K_HARDWARE_SERIAL
|
||||||
|
TMC_UART_DEFINE(HW, K, K);
|
||||||
|
#define K_HAS_HW_SERIAL 1
|
||||||
|
#else
|
||||||
|
TMC_UART_DEFINE(SW, K, K);
|
||||||
|
#define K_HAS_SW_SERIAL 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AXIS_HAS_UART(E0)
|
#if AXIS_HAS_UART(E0)
|
||||||
#ifdef E0_HARDWARE_SERIAL
|
#ifdef E0_HARDWARE_SERIAL
|
||||||
TMC_UART_DEFINE_E(HW, 0);
|
TMC_UART_DEFINE_E(HW, 0);
|
||||||
|
@ -402,7 +439,9 @@ enum StealthIndex : uint8_t {
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z), X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, E6, E7, TOTAL };
|
#define _EN_ITEM(N) , E##N
|
||||||
|
enum TMCAxis : uint8_t { LINEAR_AXIS_LIST(X, Y, Z, I, J, K), X2, Y2, Z2, Z3, Z4 REPEAT(EXTRUDERS, _EN_ITEM), TOTAL };
|
||||||
|
#undef _EN_ITEM
|
||||||
|
|
||||||
void tmc_serial_begin() {
|
void tmc_serial_begin() {
|
||||||
#if HAS_TMC_HW_SERIAL
|
#if HAS_TMC_HW_SERIAL
|
||||||
|
@ -474,6 +513,27 @@ enum StealthIndex : uint8_t {
|
||||||
stepperZ4.beginSerial(TMC_BAUD_RATE);
|
stepperZ4.beginSerial(TMC_BAUD_RATE);
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_HAS_UART(I)
|
||||||
|
#ifdef I_HARDWARE_SERIAL
|
||||||
|
HW_SERIAL_BEGIN(I);
|
||||||
|
#else
|
||||||
|
stepperI.beginSerial(TMC_BAUD_RATE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_UART(J)
|
||||||
|
#ifdef J_HARDWARE_SERIAL
|
||||||
|
HW_SERIAL_BEGIN(J);
|
||||||
|
#else
|
||||||
|
stepperJ.beginSerial(TMC_BAUD_RATE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_UART(K)
|
||||||
|
#ifdef K_HARDWARE_SERIAL
|
||||||
|
HW_SERIAL_BEGIN(K);
|
||||||
|
#else
|
||||||
|
stepperK.beginSerial(TMC_BAUD_RATE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#if AXIS_HAS_UART(E0)
|
#if AXIS_HAS_UART(E0)
|
||||||
#ifdef E0_HARDWARE_SERIAL
|
#ifdef E0_HARDWARE_SERIAL
|
||||||
HW_SERIAL_BEGIN(E0);
|
HW_SERIAL_BEGIN(E0);
|
||||||
|
@ -740,6 +800,15 @@ void restore_trinamic_drivers() {
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
stepperZ4.push();
|
stepperZ4.push();
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
stepperI.push();
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
stepperJ.push();
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
stepperK.push();
|
||||||
|
#endif
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
stepperE0.push();
|
stepperE0.push();
|
||||||
#endif
|
#endif
|
||||||
|
@ -771,7 +840,10 @@ void reset_trinamic_drivers() {
|
||||||
ENABLED(STEALTHCHOP_E),
|
ENABLED(STEALTHCHOP_E),
|
||||||
ENABLED(STEALTHCHOP_XY),
|
ENABLED(STEALTHCHOP_XY),
|
||||||
ENABLED(STEALTHCHOP_XY),
|
ENABLED(STEALTHCHOP_XY),
|
||||||
ENABLED(STEALTHCHOP_Z)
|
ENABLED(STEALTHCHOP_Z),
|
||||||
|
ENABLED(STEALTHCHOP_I),
|
||||||
|
ENABLED(STEALTHCHOP_J),
|
||||||
|
ENABLED(STEALTHCHOP_K)
|
||||||
);
|
);
|
||||||
|
|
||||||
#if AXIS_IS_TMC(X)
|
#if AXIS_IS_TMC(X)
|
||||||
|
@ -798,6 +870,15 @@ void reset_trinamic_drivers() {
|
||||||
#if AXIS_IS_TMC(Z4)
|
#if AXIS_IS_TMC(Z4)
|
||||||
TMC_INIT(Z4, STEALTH_AXIS_Z);
|
TMC_INIT(Z4, STEALTH_AXIS_Z);
|
||||||
#endif
|
#endif
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
TMC_INIT(I, STEALTH_AXIS_I);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
TMC_INIT(J, STEALTH_AXIS_J);
|
||||||
|
#endif
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
TMC_INIT(K, STEALTH_AXIS_K);
|
||||||
|
#endif
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
TMC_INIT(E0, STEALTH_AXIS_E);
|
TMC_INIT(E0, STEALTH_AXIS_E);
|
||||||
#endif
|
#endif
|
||||||
|
@ -848,6 +929,24 @@ void reset_trinamic_drivers() {
|
||||||
stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY));
|
stepperZ4.homing_threshold(CAT(TERN(Z4_SENSORLESS, Z4, Z), _STALL_SENSITIVITY));
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
#if I_SENSORLESS
|
||||||
|
stepperI.homing_threshold(I_STALL_SENSITIVITY);
|
||||||
|
#if AXIS_HAS_STALLGUARD(I)
|
||||||
|
stepperI.homing_threshold(CAT(TERN(I_SENSORLESS, I, I), _STALL_SENSITIVITY));
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if J_SENSORLESS
|
||||||
|
stepperJ.homing_threshold(J_STALL_SENSITIVITY);
|
||||||
|
#if AXIS_HAS_STALLGUARD(J)
|
||||||
|
stepperJ.homing_threshold(CAT(TERN(J_SENSORLESS, J, J), _STALL_SENSITIVITY));
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if K_SENSORLESS
|
||||||
|
stepperK.homing_threshold(K_STALL_SENSITIVITY);
|
||||||
|
#if AXIS_HAS_STALLGUARD(K)
|
||||||
|
stepperK.homing_threshold(CAT(TERN(K_SENSORLESS, K, K), _STALL_SENSITIVITY));
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#endif // USE SENSORLESS
|
#endif // USE SENSORLESS
|
||||||
|
|
||||||
#ifdef TMC_ADV
|
#ifdef TMC_ADV
|
||||||
|
|
|
@ -46,6 +46,10 @@
|
||||||
#define TMC_Y_LABEL 'Y', '0'
|
#define TMC_Y_LABEL 'Y', '0'
|
||||||
#define TMC_Z_LABEL 'Z', '0'
|
#define TMC_Z_LABEL 'Z', '0'
|
||||||
|
|
||||||
|
#define TMC_I_LABEL 'I', '0'
|
||||||
|
#define TMC_J_LABEL 'J', '0'
|
||||||
|
#define TMC_K_LABEL 'K', '0'
|
||||||
|
|
||||||
#define TMC_X2_LABEL 'X', '2'
|
#define TMC_X2_LABEL 'X', '2'
|
||||||
#define TMC_Y2_LABEL 'Y', '2'
|
#define TMC_Y2_LABEL 'Y', '2'
|
||||||
#define TMC_Z2_LABEL 'Z', '2'
|
#define TMC_Z2_LABEL 'Z', '2'
|
||||||
|
@ -79,13 +83,22 @@ typedef struct {
|
||||||
#ifndef CHOPPER_TIMING_X
|
#ifndef CHOPPER_TIMING_X
|
||||||
#define CHOPPER_TIMING_X CHOPPER_TIMING
|
#define CHOPPER_TIMING_X CHOPPER_TIMING
|
||||||
#endif
|
#endif
|
||||||
#ifndef CHOPPER_TIMING_Y
|
#if HAS_Y_AXIS && !defined(CHOPPER_TIMING_Y)
|
||||||
#define CHOPPER_TIMING_Y CHOPPER_TIMING
|
#define CHOPPER_TIMING_Y CHOPPER_TIMING
|
||||||
#endif
|
#endif
|
||||||
#ifndef CHOPPER_TIMING_Z
|
#if HAS_Z_AXIS && !defined(CHOPPER_TIMING_Z)
|
||||||
#define CHOPPER_TIMING_Z CHOPPER_TIMING
|
#define CHOPPER_TIMING_Z CHOPPER_TIMING
|
||||||
#endif
|
#endif
|
||||||
#ifndef CHOPPER_TIMING_E
|
#if LINEAR_AXES >= 4 && !defined(CHOPPER_TIMING_I)
|
||||||
|
#define CHOPPER_TIMING_I CHOPPER_TIMING
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 5 && !defined(CHOPPER_TIMING_J)
|
||||||
|
#define CHOPPER_TIMING_J CHOPPER_TIMING
|
||||||
|
#endif
|
||||||
|
#if LINEAR_AXES >= 6 && !defined(CHOPPER_TIMING_K)
|
||||||
|
#define CHOPPER_TIMING_K CHOPPER_TIMING
|
||||||
|
#endif
|
||||||
|
#if HAS_EXTRUDERS && !defined(CHOPPER_TIMING_E)
|
||||||
#define CHOPPER_TIMING_E CHOPPER_TIMING
|
#define CHOPPER_TIMING_E CHOPPER_TIMING
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -225,6 +238,48 @@ void reset_trinamic_drivers();
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// I Stepper
|
||||||
|
#if AXIS_IS_TMC(I)
|
||||||
|
extern TMC_CLASS(I, I) stepperI;
|
||||||
|
static constexpr chopper_timing_t chopper_timing_I = CHOPPER_TIMING_I;
|
||||||
|
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
|
||||||
|
#define I_ENABLE_INIT() NOOP
|
||||||
|
#define I_ENABLE_WRITE(STATE) stepperI.toff((STATE)==I_ENABLE_ON ? chopper_timing.toff : 0)
|
||||||
|
#define I_ENABLE_READ() stepperI.isEnabled()
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SQUARE_WAVE(I)
|
||||||
|
#define I_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(I_STEP_PIN); }while(0)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// J Stepper
|
||||||
|
#if AXIS_IS_TMC(J)
|
||||||
|
extern TMC_CLASS(J, J) stepperJ;
|
||||||
|
static constexpr chopper_timing_t chopper_timing_J = CHOPPER_TIMING_J;
|
||||||
|
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
|
||||||
|
#define J_ENABLE_INIT() NOOP
|
||||||
|
#define J_ENABLE_WRITE(STATE) stepperJ.toff((STATE)==J_ENABLE_ON ? chopper_timing.toff : 0)
|
||||||
|
#define J_ENABLE_READ() stepperJ.isEnabled()
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SQUARE_WAVE(J)
|
||||||
|
#define J_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(J_STEP_PIN); }while(0)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// K Stepper
|
||||||
|
#if AXIS_IS_TMC(K)
|
||||||
|
extern TMC_CLASS(K, K) stepperK;
|
||||||
|
static constexpr chopper_timing_t chopper_timing_K = CHOPPER_TIMING_K;
|
||||||
|
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
|
||||||
|
#define K_ENABLE_INIT() NOOP
|
||||||
|
#define K_ENABLE_WRITE(STATE) stepperK.toff((STATE)==K_ENABLE_ON ? chopper_timing.toff : 0)
|
||||||
|
#define K_ENABLE_READ() stepperK.isEnabled()
|
||||||
|
#endif
|
||||||
|
#if AXIS_HAS_SQUARE_WAVE(K)
|
||||||
|
#define K_STEP_WRITE(STATE) do{ if (STATE) TOGGLE(K_STEP_PIN); }while(0)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
// E0 Stepper
|
// E0 Stepper
|
||||||
#if AXIS_IS_TMC(E0)
|
#if AXIS_IS_TMC(E0)
|
||||||
extern TMC_CLASS_E(0) stepperE0;
|
extern TMC_CLASS_E(0) stepperE0;
|
||||||
|
|
|
@ -49,7 +49,9 @@
|
||||||
bool toolchange_extruder_ready[EXTRUDERS];
|
bool toolchange_extruder_ready[EXTRUDERS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) || (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0)
|
#if EITHER(MAGNETIC_PARKING_EXTRUDER, TOOL_SENSOR) \
|
||||||
|
|| defined(EVENT_GCODE_TOOLCHANGE_T0) || defined(EVENT_GCODE_TOOLCHANGE_T1) || defined(EVENT_GCODE_AFTER_TOOLCHANGE) \
|
||||||
|
|| (ENABLED(PARKING_EXTRUDER) && PARKING_EXTRUDER_SOLENOIDS_DELAY > 0)
|
||||||
#include "../gcode/gcode.h"
|
#include "../gcode/gcode.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1311,10 +1313,22 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
|
||||||
|
|
||||||
TERN_(HAS_FANMUX, fanmux_switch(active_extruder));
|
TERN_(HAS_FANMUX, fanmux_switch(active_extruder));
|
||||||
|
|
||||||
|
if (!no_move) {
|
||||||
|
#ifdef EVENT_GCODE_TOOLCHANGE_T0
|
||||||
|
if (new_tool == 0)
|
||||||
|
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T0));
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef EVENT_GCODE_TOOLCHANGE_T1
|
||||||
|
if (new_tool == 1)
|
||||||
|
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_TOOLCHANGE_T1));
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef EVENT_GCODE_AFTER_TOOLCHANGE
|
#ifdef EVENT_GCODE_AFTER_TOOLCHANGE
|
||||||
if (!no_move && TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE))
|
if (TERN1(DUAL_X_CARRIAGE, dual_x_carriage_mode == DXC_AUTO_PARK_MODE))
|
||||||
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE));
|
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE));
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder);
|
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder);
|
||||||
|
|
||||||
|
|
|
@ -1319,6 +1319,105 @@
|
||||||
#if PIN_EXISTS(Z_MIN_PROBE)
|
#if PIN_EXISTS(Z_MIN_PROBE)
|
||||||
REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN)
|
REPORT_NAME_DIGITAL(__LINE__, Z_MIN_PROBE_PIN)
|
||||||
#endif
|
#endif
|
||||||
|
#if PIN_EXISTS(I_ATT)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_ATT_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_CS)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_CS_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_DIR)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_DIR_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_ENABLE)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_ENABLE_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MAX)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_MAX_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MIN)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_MIN_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS1)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_MS1_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS2)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_MS2_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS3)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_MS3_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_STEP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_STEP_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_STOP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, I_STOP_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_ATT)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_ATT_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_CS)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_CS_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_DIR)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_DIR_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_ENABLE)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_ENABLE_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MAX)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_MAX_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MIN)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_MIN_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS1)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_MS1_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS2)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_MS2_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS3)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_MS3_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_STEP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_STEP_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_STOP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, J_STOP_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_ATT)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_ATT_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_CS)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_CS_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_DIR)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_DIR_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_ENABLE)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_ENABLE_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MAX)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_MAX_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MIN)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_MIN_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS1)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_MS1_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS2)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_MS2_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS3)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_MS3_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_STEP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_STEP_PIN)
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_STOP)
|
||||||
|
REPORT_NAME_DIGITAL(__LINE__, K_STOP_PIN)
|
||||||
|
#endif
|
||||||
#if PIN_EXISTS(ZRIB_V20_D6)
|
#if PIN_EXISTS(ZRIB_V20_D6)
|
||||||
REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
|
REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -402,7 +402,8 @@
|
||||||
#define X_STOP_PIN X_MAX_PIN
|
#define X_STOP_PIN X_MAX_PIN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef Y_STOP_PIN
|
#if HAS_Y_AXIS
|
||||||
|
#ifdef Y_STOP_PIN
|
||||||
#if Y_HOME_TO_MIN
|
#if Y_HOME_TO_MIN
|
||||||
#define Y_MIN_PIN Y_STOP_PIN
|
#define Y_MIN_PIN Y_STOP_PIN
|
||||||
#ifndef Y_MAX_PIN
|
#ifndef Y_MAX_PIN
|
||||||
|
@ -414,13 +415,15 @@
|
||||||
#define Y_MIN_PIN -1
|
#define Y_MIN_PIN -1
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#elif Y_HOME_TO_MIN
|
#elif Y_HOME_TO_MIN
|
||||||
#define Y_STOP_PIN Y_MIN_PIN
|
#define Y_STOP_PIN Y_MIN_PIN
|
||||||
#else
|
#else
|
||||||
#define Y_STOP_PIN Y_MAX_PIN
|
#define Y_STOP_PIN Y_MAX_PIN
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef Z_STOP_PIN
|
#if HAS_Z_AXIS
|
||||||
|
#ifdef Z_STOP_PIN
|
||||||
#if Z_HOME_TO_MIN
|
#if Z_HOME_TO_MIN
|
||||||
#define Z_MIN_PIN Z_STOP_PIN
|
#define Z_MIN_PIN Z_STOP_PIN
|
||||||
#ifndef Z_MAX_PIN
|
#ifndef Z_MAX_PIN
|
||||||
|
@ -432,10 +435,56 @@
|
||||||
#define Z_MIN_PIN -1
|
#define Z_MIN_PIN -1
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#elif Z_HOME_TO_MIN
|
#elif Z_HOME_TO_MIN
|
||||||
#define Z_STOP_PIN Z_MIN_PIN
|
#define Z_STOP_PIN Z_MIN_PIN
|
||||||
#else
|
#else
|
||||||
#define Z_STOP_PIN Z_MAX_PIN
|
#define Z_STOP_PIN Z_MAX_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 4
|
||||||
|
#ifdef I_STOP_PIN
|
||||||
|
#if I_HOME_TO_MIN
|
||||||
|
#define I_MIN_PIN I_STOP_PIN
|
||||||
|
#define I_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define I_MIN_PIN -1
|
||||||
|
#define I_MAX_PIN I_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#undef I_MIN_PIN
|
||||||
|
#undef I_MAX_PIN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
#ifdef J_STOP_PIN
|
||||||
|
#if J_HOME_TO_MIN
|
||||||
|
#define J_MIN_PIN J_STOP_PIN
|
||||||
|
#define J_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define J_MIN_PIN -1
|
||||||
|
#define J_MAX_PIN J_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#undef J_MIN_PIN
|
||||||
|
#undef J_MAX_PIN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
#ifdef K_STOP_PIN
|
||||||
|
#if K_HOME_TO_MIN
|
||||||
|
#define K_MIN_PIN K_STOP_PIN
|
||||||
|
#define K_MAX_PIN -1
|
||||||
|
#else
|
||||||
|
#define K_MIN_PIN -1
|
||||||
|
#define K_MAX_PIN K_STOP_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#undef K_MIN_PIN
|
||||||
|
#undef K_MAX_PIN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Filament Sensor first pin alias
|
// Filament Sensor first pin alias
|
||||||
|
@ -863,6 +912,19 @@
|
||||||
#undef Z_MAX_PIN
|
#undef Z_MAX_PIN
|
||||||
#define Z_MAX_PIN -1
|
#define Z_MAX_PIN -1
|
||||||
#endif
|
#endif
|
||||||
|
#if DISABLED(USE_IMAX_PLUG)
|
||||||
|
#undef I_MAX_PIN
|
||||||
|
#define I_MAX_PIN -1
|
||||||
|
#endif
|
||||||
|
#if DISABLED(USE_JMAX_PLUG)
|
||||||
|
#undef J_MAX_PIN
|
||||||
|
#define J_MAX_PIN -1
|
||||||
|
#endif
|
||||||
|
#if DISABLED(USE_KMAX_PLUG)
|
||||||
|
#undef K_MAX_PIN
|
||||||
|
#define K_MAX_PIN -1
|
||||||
|
#endif
|
||||||
|
|
||||||
#if DISABLED(USE_XMIN_PLUG)
|
#if DISABLED(USE_XMIN_PLUG)
|
||||||
#undef X_MIN_PIN
|
#undef X_MIN_PIN
|
||||||
#define X_MIN_PIN -1
|
#define X_MIN_PIN -1
|
||||||
|
@ -906,6 +968,19 @@
|
||||||
#undef Z4_MAX_PIN
|
#undef Z4_MAX_PIN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if DISABLED(USE_IMIN_PLUG)
|
||||||
|
#undef I_MIN_PIN
|
||||||
|
#define I_MIN_PIN -1
|
||||||
|
#endif
|
||||||
|
#if DISABLED(USE_JMIN_PLUG)
|
||||||
|
#undef J_MIN_PIN
|
||||||
|
#define J_MIN_PIN -1
|
||||||
|
#endif
|
||||||
|
#if DISABLED(USE_KMIN_PLUG)
|
||||||
|
#undef K_MIN_PIN
|
||||||
|
#define K_MIN_PIN -1
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Default DOGLCD SPI delays
|
// Default DOGLCD SPI delays
|
||||||
//
|
//
|
||||||
|
|
|
@ -63,81 +63,220 @@
|
||||||
|
|
||||||
#define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS
|
#define _X_PINS X_STEP_PIN, X_DIR_PIN, _X_ENABLE_PIN _X_MIN _X_MAX _X_MS1 _X_MS2 _X_MS3 _X_CS
|
||||||
|
|
||||||
#if PIN_EXISTS(Y_MIN)
|
#if HAS_Y_AXIS
|
||||||
|
|
||||||
|
#if PIN_EXISTS(Y_MIN)
|
||||||
#define _Y_MIN Y_MIN_PIN,
|
#define _Y_MIN Y_MIN_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_MIN
|
#define _Y_MIN
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MAX)
|
#if PIN_EXISTS(Y_MAX)
|
||||||
#define _Y_MAX Y_MAX_PIN,
|
#define _Y_MAX Y_MAX_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_MAX
|
#define _Y_MAX
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y)
|
#if PIN_EXISTS(Y_CS) && AXIS_HAS_SPI(Y)
|
||||||
#define _Y_CS Y_CS_PIN,
|
#define _Y_CS Y_CS_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_CS
|
#define _Y_CS
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MS1)
|
#if PIN_EXISTS(Y_MS1)
|
||||||
#define _Y_MS1 Y_MS1_PIN,
|
#define _Y_MS1 Y_MS1_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_MS1
|
#define _Y_MS1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MS2)
|
#if PIN_EXISTS(Y_MS2)
|
||||||
#define _Y_MS2 Y_MS2_PIN,
|
#define _Y_MS2 Y_MS2_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_MS2
|
#define _Y_MS2
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_MS3)
|
#if PIN_EXISTS(Y_MS3)
|
||||||
#define _Y_MS3 Y_MS3_PIN,
|
#define _Y_MS3 Y_MS3_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_MS3
|
#define _Y_MS3
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Y_ENABLE)
|
#if PIN_EXISTS(Y_ENABLE)
|
||||||
#define _Y_ENABLE_PIN Y_ENABLE_PIN,
|
#define _Y_ENABLE_PIN Y_ENABLE_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Y_ENABLE_PIN
|
#define _Y_ENABLE_PIN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define _Y_PINS
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define _Y_PINS Y_STEP_PIN, Y_DIR_PIN, _Y_ENABLE_PIN _Y_MIN _Y_MAX _Y_MS1 _Y_MS2 _Y_MS3 _Y_CS
|
#if HAS_Z_AXIS
|
||||||
|
|
||||||
#if PIN_EXISTS(Z_MIN)
|
#if PIN_EXISTS(Z_MIN)
|
||||||
#define _Z_MIN Z_MIN_PIN,
|
#define _Z_MIN Z_MIN_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_MIN
|
#define _Z_MIN
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MAX)
|
#if PIN_EXISTS(Z_MAX)
|
||||||
#define _Z_MAX Z_MAX_PIN,
|
#define _Z_MAX Z_MAX_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_MAX
|
#define _Z_MAX
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z)
|
#if PIN_EXISTS(Z_CS) && AXIS_HAS_SPI(Z)
|
||||||
#define _Z_CS Z_CS_PIN,
|
#define _Z_CS Z_CS_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_CS
|
#define _Z_CS
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MS1)
|
#if PIN_EXISTS(Z_MS1)
|
||||||
#define _Z_MS1 Z_MS1_PIN,
|
#define _Z_MS1 Z_MS1_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_MS1
|
#define _Z_MS1
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MS2)
|
#if PIN_EXISTS(Z_MS2)
|
||||||
#define _Z_MS2 Z_MS2_PIN,
|
#define _Z_MS2 Z_MS2_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_MS2
|
#define _Z_MS2
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_MS3)
|
#if PIN_EXISTS(Z_MS3)
|
||||||
#define _Z_MS3 Z_MS3_PIN,
|
#define _Z_MS3 Z_MS3_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_MS3
|
#define _Z_MS3
|
||||||
#endif
|
#endif
|
||||||
#if PIN_EXISTS(Z_ENABLE)
|
#if PIN_EXISTS(Z_ENABLE)
|
||||||
#define _Z_ENABLE_PIN Z_ENABLE_PIN,
|
#define _Z_ENABLE_PIN Z_ENABLE_PIN,
|
||||||
#else
|
#else
|
||||||
#define _Z_ENABLE_PIN
|
#define _Z_ENABLE_PIN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define _Z_PINS
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define _Z_PINS Z_STEP_PIN, Z_DIR_PIN, _Z_ENABLE_PIN _Z_MIN _Z_MAX _Z_MS1 _Z_MS2 _Z_MS3 _Z_CS
|
#if LINEAR_AXES >= 4
|
||||||
|
|
||||||
|
#if PIN_EXISTS(I_MIN)
|
||||||
|
#define _I_MIN I_MIN_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_MIN
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MAX)
|
||||||
|
#define _I_MAX I_MAX_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_MAX
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_CS)
|
||||||
|
#define _I_CS I_CS_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_CS
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS1)
|
||||||
|
#define _I_MS1 I_MS1_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_MS1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS2)
|
||||||
|
#define _I_MS2 I_MS2_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_MS2
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(I_MS3)
|
||||||
|
#define _I_MS3 I_MS3_PIN,
|
||||||
|
#else
|
||||||
|
#define _I_MS3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _I_PINS I_STEP_PIN, I_DIR_PIN, I_ENABLE_PIN, _I_MIN _I_MAX _I_MS1 _I_MS2 _I_MS3 _I_CS
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define _I_PINS
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 5
|
||||||
|
|
||||||
|
#if PIN_EXISTS(J_MIN)
|
||||||
|
#define _J_MIN J_MIN_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_MIN
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MAX)
|
||||||
|
#define _J_MAX J_MAX_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_MAX
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_CS)
|
||||||
|
#define _J_CS J_CS_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_CS
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS1)
|
||||||
|
#define _J_MS1 J_MS1_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_MS1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS2)
|
||||||
|
#define _J_MS2 J_MS2_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_MS2
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(J_MS3)
|
||||||
|
#define _J_MS3 J_MS3_PIN,
|
||||||
|
#else
|
||||||
|
#define _J_MS3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _J_PINS J_STEP_PIN, J_DIR_PIN, J_ENABLE_PIN, _J_MIN _J_MAX _J_MS1 _J_MS2 _J_MS3 _J_CS
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define _J_PINS
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if LINEAR_AXES >= 6
|
||||||
|
|
||||||
|
#if PIN_EXISTS(K_MIN)
|
||||||
|
#define _K_MIN K_MIN_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_MIN
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MAX)
|
||||||
|
#define _K_MAX K_MAX_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_MAX
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_CS)
|
||||||
|
#define _K_CS K_CS_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_CS
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS1)
|
||||||
|
#define _K_MS1 K_MS1_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_MS1
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS2)
|
||||||
|
#define _K_MS2 K_MS2_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_MS2
|
||||||
|
#endif
|
||||||
|
#if PIN_EXISTS(K_MS3)
|
||||||
|
#define _K_MS3 K_MS3_PIN,
|
||||||
|
#else
|
||||||
|
#define _K_MS3
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define _K_PINS K_STEP_PIN, K_DIR_PIN, K_ENABLE_PIN, _K_MIN _K_MAX _K_MS1 _K_MS2 _K_MS3 _K_CS
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define _K_PINS
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Extruder Chip Select, Digital Micro-steps
|
// Extruder Chip Select, Digital Micro-steps
|
||||||
|
@ -714,7 +853,8 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SENSITIVE_PINS { \
|
#define SENSITIVE_PINS { \
|
||||||
_X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \
|
_X_PINS _Y_PINS _Z_PINS _I_PINS _J_PINS _K_PINS \
|
||||||
|
_X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS _Z_PROBE \
|
||||||
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \
|
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _E6_PINS _E7_PINS \
|
||||||
_H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \
|
_H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS _H6_PINS _H7_PINS \
|
||||||
_PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \
|
_PS_ON _FAN0 _FAN1 _FAN2 _FAN3 _FAN4 _FAN5 _FAN6 _FAN7 _FANC \
|
||||||
|
|
|
@ -59,6 +59,7 @@
|
||||||
|
|
||||||
// extern
|
// extern
|
||||||
|
|
||||||
|
PGMSTR(M21_STR, "M21");
|
||||||
PGMSTR(M23_STR, "M23 %s");
|
PGMSTR(M23_STR, "M23 %s");
|
||||||
PGMSTR(M24_STR, "M24");
|
PGMSTR(M24_STR, "M24");
|
||||||
|
|
||||||
|
|
Loading…
Reference in a new issue