[1.1.x] Hangprinter support (#9180)

This commit is contained in:
tobbelobb 2018-09-09 04:17:02 +02:00 committed by Scott Lahteine
parent 14bf319db8
commit 330c4bcbb9
26 changed files with 5525 additions and 739 deletions

View File

@ -77,313 +77,7 @@ script:
- cp Marlin/Configuration_adv.h Marlin/Configuration_adv.h.backup
- cp Marlin/pins_RAMPS.h Marlin/pins_RAMPS.h.backup
#
# Build with the default configurations
# Test Hangprinter only
#
- use_example_configs hangprinter
- build_marlin
#
# Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4
# Test a "Fix Mounted" Probe with Safe Homing, some arc options,
# linear bed leveling, M48, leveling debug, and firmware retraction.
#
- opt_set MOTHERBOARD BOARD_RAMPS_14_EEB
- opt_set EXTRUDERS 2
- opt_set TEMP_SENSOR_0 -2
- opt_set TEMP_SENSOR_1 1
- opt_set TEMP_SENSOR_BED 1
- opt_set POWER_SUPPLY 1
- opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS PINS_DEBUGGING
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED AUTO_POWER_CONTROL NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR
- opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
- opt_enable_adv ARC_P_CIRCLES ADVANCED_PAUSE_FEATURE CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE
- opt_enable_adv FWRETRACT MAX7219_DEBUG LED_CONTROL_MENU CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CODEPENDENT_XY_HOMING
- opt_set GRID_MAX_POINTS_X 16
- opt_set_adv FANMUX0_PIN 53
- build_marlin
#
# Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders
#
- restore_configs
- opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO
- opt_set EXTRUDERS 5
- opt_set TEMP_SENSOR_1 1
- opt_set TEMP_SENSOR_2 5
- opt_set TEMP_SENSOR_3 20
- opt_set TEMP_SENSOR_4 999
- opt_set TEMP_SENSOR_BED 1
- opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
- opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING BABYSTEP_XY LIN_ADVANCE NANODLP_Z_SYNC QUICK_HOME JUNCTION_DEVIATION MAX7219_DEBUG
- opt_set_adv MAX7219_ROTATE 270
- build_marlin
#
# Add a Sled Z Probe, use UBL Cartesian moves, use Japanese language
#
- opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE S_CURVE_ACCELERATION
- opt_set LCD_LANGUAGE kana_utf8
- opt_disable SEGMENT_LEVELED_MOVES
- opt_enable_adv BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING
- build_marlin
#
# Test a Servo Probe
# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES
#
- restore_configs
- opt_enable NUM_SERVOS Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
- opt_set NUM_SERVOS 1
- opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
- opt_enable_adv NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
- build_marlin
#
# Test MESH_BED_LEVELING feature, with LCD
#
- restore_configs
- opt_enable MESH_BED_LEVELING G26_MESH_EDITING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER
- build_marlin
#
# Test MINIRAMBO for PWM_MOTOR_CURRENT
# PROBE_MANUALLY feature, with LCD support,
# ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
# PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
# Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
# ADVANCED_PAUSE_FEATURE, ADVANCED_PAUSE_CONTINUOUS_PURGE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU, M114_DETAIL
# EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER,
# INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT
#
- restore_configs
- opt_set MOTHERBOARD BOARD_MINIRAMBO
- opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR G26_MESH_EDITING LCD_BED_LEVELING ULTIMAKERCONTROLLER
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT
- opt_enable ULTIMAKERCONTROLLER SDSUPPORT
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632
- opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
- opt_enable_adv ADVANCED_PAUSE_FEATURE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
- opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250}
- opt_set_adv I2C_SLAVE_ADDRESS 63
- build_marlin
#
# Mixing Extruder with 5 steppers, Cyrillic
#
- restore_configs
- opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO
- opt_enable MIXING_EXTRUDER CR10_STOCKDISPLAY
- opt_set MIXING_STEPPERS 5
- opt_set LCD_LANGUAGE ru
- build_marlin
#
# Test DUAL_X_CARRIAGE
#
- restore_configs
- opt_set MOTHERBOARD BOARD_RUMBA
- opt_set EXTRUDERS 2
- opt_set TEMP_SENSOR_1 1
- opt_enable USE_XMAX_PLUG
- opt_enable_adv DUAL_X_CARRIAGE
- build_marlin
#
# Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER
#
#- restore_configs
#- opt_set MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D
#- opt_set LCD_FEEDBACK_FREQUENCY_DURATION_MS 10
#- opt_set LCD_FEEDBACK_FREQUENCY_HZ 100
#- opt_enable BQ_LCD_SMART_CONTROLLER SPEAKER
#
# Test SWITCHING_EXTRUDER
#
- restore_configs
- opt_set MOTHERBOARD BOARD_RUMBA
- opt_set EXTRUDERS 2
- opt_enable NUM_SERVOS
- opt_set NUM_SERVOS 1
- opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER
- build_marlin
#
# Enable COREXY
#
#- restore_configs
#- opt_enable COREXY
#- build_marlin
#
# Test many less common options
#
- restore_configs
- opt_enable COREYX
- opt_set_adv FAN_MIN_PWM 50
- opt_set_adv FAN_KICKSTART_TIME 100
- opt_set_adv XY_FREQUENCY_LIMIT 15
- opt_enable_adv SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME
- opt_enable_adv ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED ADVANCED_OK
- opt_enable_adv VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL
- opt_enable_adv EXTRA_FAN_SPEED FWERETRACT Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
- opt_enable_adv MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT
- opt_enable FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR
- opt_enable ENDSTOP_INTERRUPTS_FEATURE FAN_SOFT_PWM SDSUPPORT
- opt_enable USE_XMAX_PLUG
- build_marlin
#
######## Other Standard LCD/Panels ##############
#
# ULTRA_LCD
#
#- restore_configs
#- opt_enable ULTRA_LCD
#- build_marlin
#
# DOGLCD
#
#- restore_configs
#- opt_enable DOGLCD
#- build_marlin
#
# MAKRPANEL
# Needs to use Melzi and Sanguino hardware
#
#- restore_configs
#- opt_enable MAKRPANEL
#- build_marlin
#
# REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, BABYSTEPPING, RIGIDBOARD_V2, and DAC_MOTOR_CURRENT_DEFAULT
#
#- restore_configs
#- opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2
#- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT
#- build_marlin
# #
# G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING
#
#- restore_configs
#- opt_enable G3D_PANEL SDSUPPORT
#- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
#- opt_set_adv SDSORT_GCODE true
#- opt_set_adv SDSORT_USES_RAM true
#- opt_set_adv SDSORT_USES_STACK true
#- opt_set_adv SDSORT_CACHE_NAMES true
#- build_marlin
#
# REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with LIGHTWEIGHT_UI
#
- restore_configs
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES LIGHTWEIGHT_UI
- opt_set_adv SDSORT_GCODE true
- opt_set_adv SDSORT_USES_RAM true
- opt_set_adv SDSORT_USES_STACK true
- opt_set_adv SDSORT_CACHE_NAMES true
- build_marlin
#
# REPRAPWORLD_KEYPAD
#
# Cant find configuration details to get it to compile
#- restore_configs
#- opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP
#- build_marlin
#
# RA_CONTROL_PANEL
#
#- restore_configs
#- opt_enable RA_CONTROL_PANEL PINS_DEBUGGING
#- build_marlin
#
######## I2C LCD/PANELS ##############
#
# !!!ATTENTION!!!
# Most I2C configurations are failing at the moment because they require
# a different Liquid Crystal library "LiquidTWI2".
#
# LCD_SAINSMART_I2C_1602
#
#- restore_configs
#- opt_enable LCD_SAINSMART_I2C_1602
#- build_marlin
#
# LCD_I2C_PANELOLU2
#
#- restore_configs
#- opt_enable LCD_I2C_PANELOLU2
#- build_marlin
#
# LCD_I2C_VIKI
#
#- restore_configs
#- opt_enable LCD_I2C_VIKI
#- build_marlin
#
# LCM1602
#
#- restore_configs
#- opt_enable LCM1602
#- build_marlin
#
# Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#
#- restore_configs
#- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
#- for lang in an bg ca zh_CN zh_TW cz da de el el-gr en es eu fi fr gl hr it jp-kana nl pl pt pt-br ru sk tr uk test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; build_marlin
#
#- restore_configs
#- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT
#- for lang in an bg ca zh_CN zh_TW cz da de el el-gr en es eu fi fr gl hr it jp-kana nl pl pt pt-br ru sk tr uk test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; build_marlin
#
#
######## Example Configurations ##############
#
# BQ Hephestos 2
#- restore_configs
#- use_example_configs Hephestos_2
#- build_marlin
#
# Delta Config (generic) + ABL bilinear + PROBE_MANUALLY
- use_example_configs delta/generic
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY
- build_marlin
#
# Delta Config (generic) + UBL + ALLEN_KEY + OLED_PANEL_TINYBOY2 + EEPROM_SETTINGS
#
- use_example_configs delta/generic
- opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT
- opt_enable OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY
- build_marlin
#
# Delta Config (FLSUN AC because it's complex)
#
- use_example_configs delta/FLSUN/auto_calibrate
- build_marlin
#
# Makibox Config need to check board type for Teensy++ 2.0
#
#- use_example_configs makibox
#- build_marlin
#
# SCARA with TMC2130
#
- use_example_configs SCARA
- opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
- opt_set X_DRIVER_TYPE TMC2130
- opt_set Y_DRIVER_TYPE TMC2130
- opt_set Z_DRIVER_TYPE TMC2130
- opt_set E0_DRIVER_TYPE TMC2130
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD SENSORLESS_HOMING
- build_marlin
#
# TMC2208 Config
#
- restore_configs
- opt_set X_DRIVER_TYPE TMC2208
- opt_set Y_DRIVER_TYPE TMC2208
- opt_set Z_DRIVER_TYPE TMC2208
- opt_set E0_DRIVER_TYPE TMC2208
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG
- build_marlin
#
# tvrrug Config need to check board type for sanguino atmega644p
#
#- use_example_configs tvrrug/Round2
#- build_marlin
#
#
######## Board Types #############
#
# To be added in nightly test branch
#

View File

@ -439,10 +439,20 @@
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
#define XYZE_N (XYZ + E_STEPPERS)
#if ENABLED(HANGPRINTER)
#define NUM_AXIS_N (ABCD + E_STEPPERS)
#else
#define NUM_AXIS_N (XYZ + E_STEPPERS)
#endif
#define E_AXIS_N (E_AXIS + extruder)
#else
#undef DISTINCT_E_FACTORS
#define XYZE_N XYZE
#if ENABLED(HANGPRINTER)
#define NUM_AXIS_N ABCDE
#else
#define NUM_AXIS_N XYZE
#endif
#define E_AXIS_N E_AXIS
#endif

View File

@ -29,7 +29,7 @@
#define CONDITIONALS_POST_H
#define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA || ENABLED(HANGPRINTER))
#define IS_CARTESIAN !IS_KINEMATIC
/**
@ -47,7 +47,7 @@
#define Y_BED_SIZE Y_MAX_LENGTH
#endif
// Require 0,0 bed center for Delta and SCARA
// Require 0,0 bed center for Delta, SCARA, and HANGPRINTER
#if IS_KINEMATIC
#define BED_CENTER_AT_0_0
#endif
@ -129,7 +129,7 @@
#ifdef MANUAL_X_HOME_POS
#define X_HOME_POS MANUAL_X_HOME_POS
#elif ENABLED(BED_CENTER_AT_0_0)
#if ENABLED(DELTA)
#if ENABLED(DELTA) || ENABLED(HANGPRINTER)
#define X_HOME_POS 0
#else
#define X_HOME_POS ((X_BED_SIZE) * (X_HOME_DIR) * 0.5)
@ -145,7 +145,7 @@
#ifdef MANUAL_Y_HOME_POS
#define Y_HOME_POS MANUAL_Y_HOME_POS
#elif ENABLED(BED_CENTER_AT_0_0)
#if ENABLED(DELTA)
#if (ENABLED(DELTA) || ENABLED(HANGPRINTER))
#define Y_HOME_POS 0
#else
#define Y_HOME_POS ((Y_BED_SIZE) * (Y_HOME_DIR) * 0.5)
@ -729,6 +729,28 @@
#define HAS_E4_MICROSTEPS (PIN_EXISTS(E4_MS1))
#define HAS_SOLENOID_4 (PIN_EXISTS(SOL4))
#if ENABLED(HANGPRINTER)
#define HAS_A_ENABLE (PIN_EXISTS(A_ENABLE))
#define HAS_A_DIR (PIN_EXISTS(A_DIR))
#define HAS_A_STEP (PIN_EXISTS(A_STEP))
#define HAS_A_MICROSTEPS (PIN_EXISTS(A_MS1))
#define HAS_B_ENABLE (PIN_EXISTS(B_ENABLE))
#define HAS_B_DIR (PIN_EXISTS(B_DIR))
#define HAS_B_STEP (PIN_EXISTS(B_STEP))
#define HAS_B_MICROSTEPS (PIN_EXISTS(B_MS1))
#define HAS_C_ENABLE (PIN_EXISTS(C_ENABLE))
#define HAS_C_DIR (PIN_EXISTS(C_DIR))
#define HAS_C_STEP (PIN_EXISTS(C_STEP))
#define HAS_C_MICROSTEPS (PIN_EXISTS(C_MS1))
#define HAS_D_ENABLE (PIN_EXISTS(D_ENABLE))
#define HAS_D_DIR (PIN_EXISTS(D_DIR))
#define HAS_D_STEP (PIN_EXISTS(D_STEP))
#define HAS_D_MICROSTEPS (PIN_EXISTS(D_MS1))
#endif
// Trinamic Stepper Drivers
#define HAS_STEALTHCHOP (HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2208))
#define HAS_STALLGUARD HAS_DRIVER(TMC2130)
@ -1379,4 +1401,17 @@
#define HAS_FOLDER_SORTING (FOLDER_SORTING || ENABLED(SDSORT_GCODE))
#endif
/**
* MOV_AXIS: number of independent axes driving the tool head's translational movement
* NUM_AXIS: number of movement axes + 1
* NUM_AXIS_N: number of movement axes + number of extruders (defined elsewhere)
*/
#if ENABLED(HANGPRINTER)
#define MOV_AXIS ABCD
#define NUM_AXIS ABCDE
#else
#define MOV_AXIS XYZ
#define NUM_AXIS XYZE
#endif
#endif // CONDITIONALS_POST_H

View File

@ -69,6 +69,13 @@
// example_configurations/SCARA and customize for your machine.
//
//===========================================================================
//============================= HANGPRINTER =================================
//===========================================================================
// For a Hangprinter start with the configuration file in the
// example_configurations/hangprinter directory and customize for your machine.
//
// @section info
// User-specified version info of this build to display in [Pronterface, etc] terminal window during

View File

@ -198,7 +198,7 @@
destination[X_AXIS] = current_position[X_AXIS];
destination[Y_AXIS] = current_position[Y_AXIS];
destination[Z_AXIS] = z; // We know the last_z==z or we wouldn't be in this block of code.
destination[E_AXIS] = current_position[E_AXIS];
destination[E_CART] = current_position[E_CART];
G26_line_to_destination(feed_value);
set_destination_from_current();
@ -212,7 +212,7 @@
destination[X_AXIS] = rx;
destination[Y_AXIS] = ry;
destination[E_AXIS] += e_delta;
destination[E_CART] += e_delta;
G26_line_to_destination(feed_value);
set_destination_from_current();
@ -254,7 +254,7 @@
while (!is_lcd_clicked()) {
lcd_chirp();
destination[E_AXIS] += 0.25;
destination[E_CART] += 0.25;
#ifdef PREVENT_LENGTHY_EXTRUDE
Total_Prime += 0.25;
if (Total_Prime >= EXTRUDE_MAXLENGTH) return G26_ERR;
@ -283,7 +283,7 @@
lcd_quick_feedback(true);
#endif
set_destination_from_current();
destination[E_AXIS] += g26_prime_length;
destination[E_CART] += g26_prime_length;
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
set_destination_from_current();
retract_filament(destination);
@ -697,7 +697,7 @@
if (turn_on_heaters() != G26_OK) goto LEAVE;
current_position[E_AXIS] = 0.0;
current_position[E_CART] = 0.0;
sync_plan_position_e();
if (g26_prime_flag && prime_nozzle() != G26_OK) goto LEAVE;
@ -812,7 +812,7 @@
const float endpoint[XYZE] = {
ex, ey,
g26_layer_height,
current_position[E_AXIS] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
current_position[E_CART] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
};
if (dist_start > 2.0) {

View File

@ -162,6 +162,42 @@ extern const char axis_codes[XYZE];
#endif // !MIXING_EXTRUDER
#if ENABLED(HANGPRINTER)
#define enable_A() enable_X()
#define enable_B() enable_Y()
#define enable_C() enable_Z()
#define __D_ENABLE(p) E##p##_ENABLE_WRITE(E_ENABLE_ON)
#define _D_ENABLE(p) __D_ENABLE(p)
#define enable_D() _D_ENABLE(EXTRUDERS)
// Don't allow any axes to be disabled
#undef disable_X
#undef disable_Y
#undef disable_Z
#define disable_X() NOOP
#define disable_Y() NOOP
#define disable_Z() NOOP
#if EXTRUDERS >= 1
#undef disable_E1
#define disable_E1() NOOP
#if EXTRUDERS >= 2
#undef disable_E2
#define disable_E2() NOOP
#if EXTRUDERS >= 3
#undef disable_E3
#define disable_E3() NOOP
#if EXTRUDERS >= 4
#undef disable_E4
#define disable_E4() NOOP
#endif // EXTRUDERS >= 4
#endif // EXTRUDERS >= 3
#endif // EXTRUDERS >= 2
#endif // EXTRUDERS >= 1
#endif // HANGPRINTER
#if ENABLED(G38_PROBE_TARGET)
extern bool G38_move, // flag to tell the interrupt handler that a G38 command is being run
G38_endstop_hit; // flag from the interrupt handler to indicate if the endstop went active
@ -304,12 +340,16 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s=0.0, bool no_move=false);
void home_all_axes();
void home_all_axes();
void report_current_position();
#if IS_KINEMATIC
extern float delta[ABC];
#if ENABLED(HANGPRINTER)
extern float line_lengths[ABCD];
#else
extern float delta[ABC];
#endif
void inverse_kinematics(const float raw[XYZ]);
#endif
@ -342,6 +382,51 @@ void report_current_position();
delta[C_AXIS] = DELTA_Z(V, C_AXIS); \
}while(0)
#elif ENABLED(HANGPRINTER)
// Don't collect anchor positions in array because there are no A_x, D_x or D_y
extern float anchor_A_y,
anchor_A_z,
anchor_B_x,
anchor_B_y,
anchor_B_z,
anchor_C_x,
anchor_C_y,
anchor_C_z,
anchor_D_z,
delta_segments_per_second,
line_lengths_origin[ABCD];
void recalc_hangprinter_settings();
#define HANGPRINTER_IK(V) do { \
line_lengths[A_AXIS] = SQRT(sq(anchor_A_z - V[Z_AXIS]) \
+ sq(anchor_A_y - V[Y_AXIS]) \
+ sq( V[X_AXIS])); \
line_lengths[B_AXIS] = SQRT(sq(anchor_B_z - V[Z_AXIS]) \
+ sq(anchor_B_y - V[Y_AXIS]) \
+ sq(anchor_B_x - V[X_AXIS])); \
line_lengths[C_AXIS] = SQRT(sq(anchor_C_z - V[Z_AXIS]) \
+ sq(anchor_C_y - V[Y_AXIS]) \
+ sq(anchor_C_x - V[X_AXIS])); \
line_lengths[D_AXIS] = SQRT(sq( V[X_AXIS]) \
+ sq( V[Y_AXIS]) \
+ sq(anchor_D_z - V[Z_AXIS])); \
}while(0)
// Inverse kinematics at origin
#define HANGPRINTER_IK_ORIGIN(LL) do { \
LL[A_AXIS] = SQRT(sq(anchor_A_z) \
+ sq(anchor_A_y)); \
LL[B_AXIS] = SQRT(sq(anchor_B_z) \
+ sq(anchor_B_y) \
+ sq(anchor_B_x)); \
LL[C_AXIS] = SQRT(sq(anchor_C_z) \
+ sq(anchor_C_y) \
+ sq(anchor_C_x)); \
LL[D_AXIS] = anchor_D_z; \
}while(0)
#elif IS_SCARA
void forward_kinematics_SCARA(const float &a, const float &b);
#endif
@ -506,6 +591,9 @@ void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm
inline bool position_is_reachable(const float &rx, const float &ry, const float inset=0) {
#if ENABLED(DELTA)
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset);
#elif ENABLED(HANGPRINTER)
// TODO: This is over simplified. Hangprinter's build volume is _not_ cylindrical.
return HYPOT2(rx, ry) <= sq(HANGPRINTER_PRINTABLE_RADIUS - inset);
#elif IS_SCARA
const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y);
return (

File diff suppressed because it is too large Load Diff

View File

@ -465,6 +465,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#if ENABLED(BABYSTEPPING)
#if ENABLED(SCARA)
#error "BABYSTEPPING is not implemented for SCARA yet."
#elif ENABLED(HANGPRINTER)
#error "BABYSTEPPING is not implemented for HANGPRINTER."
#elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
#error "BABYSTEPPING only implemented for Z axis on deltabots."
#elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && ENABLED(MESH_BED_LEVELING)
@ -527,8 +529,12 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
/**
* Individual axis homing is useless for DELTAS
*/
#if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU) && ENABLED(DELTA)
#error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics."
#if ENABLED(INDIVIDUAL_AXIS_HOMING_MENU)
#if ENABLED(DELTA)
#error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with DELTA kinematics."
#elif ENABLED(HANGPRINTER)
#error "INDIVIDUAL_AXIS_HOMING_MENU is incompatible with HANGPRINTER kinematics."
#endif
#endif
/**
@ -686,6 +692,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
* Allow only one kinematic type to be defined
*/
#if 1 < 0 \
+ ENABLED(HANGPRINTER) \
+ ENABLED(DELTA) \
+ ENABLED(MORGAN_SCARA) \
+ ENABLED(MAKERARM_SCARA) \
@ -695,7 +702,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
+ ENABLED(COREYX) \
+ ENABLED(COREZX) \
+ ENABLED(COREZY)
#error "Please enable only one of DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY."
#error "Please enable only one of HANGPRINTER, DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY."
#endif
/**
@ -717,6 +724,42 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#endif
#endif
/**
* Hangprinter requirements
*/
#if ENABLED(HANGPRINTER)
#if EXTRUDERS > 4
#error "Marlin supports a maximum of 4 EXTRUDERS when driving a Hangprinter."
#elif ENABLED(CONVENTIONAL_GEOMETRY)
#if ANCHOR_A_Y > 0
#error "ANCHOR_A_Y should be negative by convention."
#elif (ANCHOR_B_X) * (ANCHOR_C_X) > 0
#error "ANCHOR_B_X and ANCHOR_C_X should have opposite signs by convention."
#elif ANCHOR_B_Y < 0
#error "ANCHOR_B_Y should be positive by convention."
#elif ANCHOR_C_Y < 0
#error "ANCHOR_C_Y should be positive by convention."
#elif ANCHOR_A_Z > 0
#error "ANCHOR_A_Z should be negative by convention."
#elif ANCHOR_B_Z > 0
#error "ANCHOR_B_Z should be negative by convention."
#elif ANCHOR_C_Z > 0
#error "ANCHOR_C_Z should be negative by convention."
#elif ANCHOR_D_Z < 0
#error "ANCHOR_D_Z should be positive by convention."
#endif
#endif
#elif ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
#error "LINE_BUILDUP_COMPENSATION_FEATURE is only compatible with HANGPRINTER."
#endif
/**
* Mechaduino requirements
*/
#if ENABLED(MECHADUINO_I2C_COMMANDS) && DISABLED(EXPERIMENTAL_I2CBUS)
#error "MECHADUINO_I2C_COMMANDS requires EXPERIMENTAL_I2CBUS to be enabled."
#endif
/**
* Probes
*/
@ -1211,6 +1254,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#endif
#endif
#endif
/**
* Endstop Tests
*/
@ -1218,33 +1262,33 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#define _PLUG_UNUSED_TEST(AXIS,PLUG) (DISABLED(USE_##PLUG##MIN_PLUG) && DISABLED(USE_##PLUG##MAX_PLUG) && !(ENABLED(AXIS##_DUAL_ENDSTOPS) && WITHIN(AXIS##2_USE_ENDSTOP, _##PLUG##MAX_, _##PLUG##MIN_)))
#define _AXIS_PLUG_UNUSED_TEST(AXIS) (_PLUG_UNUSED_TEST(AXIS,X) && _PLUG_UNUSED_TEST(AXIS,Y) && _PLUG_UNUSED_TEST(AXIS,Z))
// At least 3 endstop plugs must be used
#if _AXIS_PLUG_UNUSED_TEST(X)
#error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
#endif
#if _AXIS_PLUG_UNUSED_TEST(Y)
#error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
#endif
#if _AXIS_PLUG_UNUSED_TEST(Z)
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
#endif
// Delta and Cartesian use 3 homing endstops
#if !IS_SCARA
#if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
#error "Enable USE_XMIN_PLUG when homing X to MIN."
#elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
#error "Enable USE_XMAX_PLUG when homing X to MAX."
#elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG)
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
#elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
#if DISABLED(HANGPRINTER)
// At least 3 endstop plugs must be used
#if _AXIS_PLUG_UNUSED_TEST(X)
#error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
#elif _AXIS_PLUG_UNUSED_TEST(Y)
#error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
#elif _AXIS_PLUG_UNUSED_TEST(Z)
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
#endif
// Delta and Cartesian use 3 homing endstops
#if !IS_SCARA
#if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
#error "Enable USE_XMIN_PLUG when homing X to MIN."
#elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
#error "Enable USE_XMAX_PLUG when homing X to MAX."
#elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG)
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
#elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
#endif
#endif
#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
#endif
#endif
#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
#endif
// Dual endstops requirements
@ -1544,17 +1588,24 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#endif
/**
* Require 4 or more elements in per-axis initializers
* Require 5/4 or more elements in per-axis initializers
*/
#if ENABLED(HANGPRINTER)
#define MIN_ELEMENTS "5"
#else
#define MIN_ELEMENTS "4"
#endif
constexpr float sanity_arr_1[] = DEFAULT_AXIS_STEPS_PER_UNIT,
sanity_arr_2[] = DEFAULT_MAX_FEEDRATE,
sanity_arr_3[] = DEFAULT_MAX_ACCELERATION;
static_assert(COUNT(sanity_arr_1) >= XYZE, "DEFAULT_AXIS_STEPS_PER_UNIT requires 4 (or more) elements.");
static_assert(COUNT(sanity_arr_2) >= XYZE, "DEFAULT_MAX_FEEDRATE requires 4 (or more) elements.");
static_assert(COUNT(sanity_arr_3) >= XYZE, "DEFAULT_MAX_ACCELERATION requires 4 (or more) elements.");
static_assert(COUNT(sanity_arr_1) <= XYZE_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements.");
static_assert(COUNT(sanity_arr_2) <= XYZE_N, "DEFAULT_MAX_FEEDRATE has too many elements.");
static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too many elements.");
static_assert(COUNT(sanity_arr_1) >= NUM_AXIS, "DEFAULT_AXIS_STEPS_PER_UNIT requires " MIN_ELEMENTS " (or more) elements for HANGPRINTER.");
static_assert(COUNT(sanity_arr_2) >= NUM_AXIS, "DEFAULT_MAX_FEEDRATE requires " MIN_ELEMENTS " (or more) elements for HANGPRINTER.");
static_assert(COUNT(sanity_arr_3) >= NUM_AXIS, "DEFAULT_MAX_ACCELERATION requires " MIN_ELEMENTS " (or more) elements for HANGPRINTER.");
static_assert(COUNT(sanity_arr_1) <= NUM_AXIS_N, "DEFAULT_AXIS_STEPS_PER_UNIT has too many elements.");
static_assert(COUNT(sanity_arr_2) <= NUM_AXIS_N, "DEFAULT_MAX_FEEDRATE has too many elements.");
static_assert(COUNT(sanity_arr_3) <= NUM_AXIS_N, "DEFAULT_MAX_ACCELERATION has too many elements.");
/**
* Sanity checks for Spindle / Laser

View File

@ -95,19 +95,19 @@ typedef struct SettingsDataStruct {
//
// DISTINCT_E_FACTORS
//
uint8_t esteppers; // XYZE_N - XYZ
uint8_t esteppers; // NUM_AXIS_N - MOV_AXIS
uint32_t planner_max_acceleration_mm_per_s2[XYZE_N], // M201 XYZE planner.max_acceleration_mm_per_s2[XYZE_N]
planner_min_segment_time_us; // M205 B planner.min_segment_time_us
float planner_axis_steps_per_mm[XYZE_N], // M92 XYZE planner.axis_steps_per_mm[XYZE_N]
planner_max_feedrate_mm_s[XYZE_N], // M203 XYZE planner.max_feedrate_mm_s[XYZE_N]
planner_acceleration, // M204 P planner.acceleration
planner_retract_acceleration, // M204 R planner.retract_acceleration
planner_travel_acceleration, // M204 T planner.travel_acceleration
planner_min_feedrate_mm_s, // M205 S planner.min_feedrate_mm_s
planner_min_travel_feedrate_mm_s, // M205 T planner.min_travel_feedrate_mm_s
planner_max_jerk[XYZE], // M205 XYZE planner.max_jerk[XYZE]
planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm
uint32_t planner_max_acceleration_mm_per_s2[NUM_AXIS_N], // M201 XYZE/ABCDE planner.max_acceleration_mm_per_s2[NUM_AXIS_N]
planner_min_segment_time_us; // M205 Q planner.min_segment_time_us
float planner_axis_steps_per_mm[NUM_AXIS_N], // M92 XYZE/ABCDE planner.axis_steps_per_mm[NUM_AXIS_N]
planner_max_feedrate_mm_s[NUM_AXIS_N], // M203 XYZE/ABCDE planner.max_feedrate_mm_s[NUM_AXIS_N]
planner_acceleration, // M204 P planner.acceleration
planner_retract_acceleration, // M204 R planner.retract_acceleration
planner_travel_acceleration, // M204 T planner.travel_acceleration
planner_min_feedrate_mm_s, // M205 S planner.min_feedrate_mm_s
planner_min_travel_feedrate_mm_s, // M205 T planner.min_travel_feedrate_mm_s
planner_max_jerk[NUM_AXIS], // M205 XYZE/ABCDE planner.max_jerk[NUM_AXIS]
planner_junction_deviation_mm; // M205 J planner.junction_deviation_mm
float home_offset[XYZ]; // M206 XYZ
@ -163,6 +163,7 @@ typedef struct SettingsDataStruct {
// DELTA / [XYZ]_DUAL_ENDSTOPS
//
#if ENABLED(DELTA)
float delta_height, // M666 H
delta_endstop_adj[ABC], // M666 XYZ
delta_radius, // M665 R
@ -170,10 +171,27 @@ typedef struct SettingsDataStruct {
delta_segments_per_second, // M665 S
delta_calibration_radius, // M665 B
delta_tower_angle_trim[ABC]; // M665 XYZ
#elif ENABLED(HANGPRINTER)
float anchor_A_y, // M665 W
anchor_A_z, // M665 E
anchor_B_x, // M665 R
anchor_B_y, // M665 T
anchor_B_z, // M665 Y
anchor_C_x, // M665 U
anchor_C_y, // M665 I
anchor_C_z, // M665 O
anchor_D_z, // M665 P
delta_segments_per_second, // M665 S
hangprinter_calibration_radius_placeholder;
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
float x_endstop_adj, // M666 X
y_endstop_adj, // M666 Y
z_endstop_adj; // M666 Z
#endif
//
@ -285,6 +303,8 @@ void MarlinSettings::postprocess() {
// planner position so the stepper counts will be set correctly.
#if ENABLED(DELTA)
recalc_delta_settings();
#elif ENABLED(HANGPRINTER)
recalc_hangprinter_settings();
#endif
#if ENABLED(PIDTEMP)
@ -418,7 +438,7 @@ void MarlinSettings::postprocess() {
_FIELD_TEST(esteppers);
const uint8_t esteppers = COUNT(planner.axis_steps_per_mm) - XYZ;
const uint8_t esteppers = NUM_AXIS_N - MOV_AXIS;
EEPROM_WRITE(esteppers);
EEPROM_WRITE(planner.max_acceleration_mm_per_s2);
@ -432,7 +452,13 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(planner.min_travel_feedrate_mm_s);
#if ENABLED(JUNCTION_DEVIATION)
const float planner_max_jerk[] = { float(DEFAULT_XJERK), float(DEFAULT_YJERK), float(DEFAULT_ZJERK), float(DEFAULT_EJERK) };
const float planner_max_jerk[] = {
#if ENABLED(HANGPRINTER)
float(DEFAULT_AJERK), float(DEFAULT_BJERK), float(DEFAULT_CJERK), float(DEFAULT_DJERK), float(DEFAULT_EJERK)
#else
float(DEFAULT_XJERK), float(DEFAULT_YJERK), float(DEFAULT_ZJERK), float(DEFAULT_EJERK)
#endif
};
EEPROM_WRITE(planner_max_jerk);
EEPROM_WRITE(planner.junction_deviation_mm);
#else
@ -560,6 +586,22 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(delta_calibration_radius); // 1 float
EEPROM_WRITE(delta_tower_angle_trim); // 3 floats
#elif ENABLED(HANGPRINTER)
dummy = 0.0f;
_FIELD_TEST(anchor_A_y);
EEPROM_WRITE(anchor_A_y); // 1 float
EEPROM_WRITE(anchor_A_z); // 1 float
EEPROM_WRITE(anchor_B_x); // 1 float
EEPROM_WRITE(anchor_B_y); // 1 float
EEPROM_WRITE(anchor_B_z); // 1 float
EEPROM_WRITE(anchor_C_x); // 1 float
EEPROM_WRITE(anchor_C_y); // 1 float
EEPROM_WRITE(anchor_C_z); // 1 float
EEPROM_WRITE(anchor_D_z); // 1 float
EEPROM_WRITE(delta_segments_per_second); // 1 float
EEPROM_WRITE(dummy); // 1 float
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
_FIELD_TEST(x_endstop_adj);
@ -1010,17 +1052,17 @@ void MarlinSettings::postprocess() {
const uint32_t def1[] = DEFAULT_MAX_ACCELERATION;
const float def2[] = DEFAULT_AXIS_STEPS_PER_UNIT, def3[] = DEFAULT_MAX_FEEDRATE;
uint32_t tmp1[XYZ + esteppers];
uint32_t tmp1[MOV_AXIS + esteppers];
EEPROM_READ(tmp1); // max_acceleration_mm_per_s2
EEPROM_READ(planner.min_segment_time_us);
float tmp2[XYZ + esteppers], tmp3[XYZ + esteppers];
float tmp2[MOV_AXIS + esteppers], tmp3[MOV_AXIS + esteppers];
EEPROM_READ(tmp2); // axis_steps_per_mm
EEPROM_READ(tmp3); // max_feedrate_mm_s
if (!validating) LOOP_XYZE_N(i) {
planner.max_acceleration_mm_per_s2[i] = i < XYZ + esteppers ? tmp1[i] : def1[i < COUNT(def1) ? i : COUNT(def1) - 1];
planner.axis_steps_per_mm[i] = i < XYZ + esteppers ? tmp2[i] : def2[i < COUNT(def2) ? i : COUNT(def2) - 1];
planner.max_feedrate_mm_s[i] = i < XYZ + esteppers ? tmp3[i] : def3[i < COUNT(def3) ? i : COUNT(def3) - 1];
if (!validating) LOOP_NUM_AXIS_N(i) {
planner.max_acceleration_mm_per_s2[i] = i < MOV_AXIS + esteppers ? tmp1[i] : def1[i < COUNT(def1) ? i : COUNT(def1) - 1];
planner.axis_steps_per_mm[i] = i < MOV_AXIS + esteppers ? tmp2[i] : def2[i < COUNT(def2) ? i : COUNT(def2) - 1];
planner.max_feedrate_mm_s[i] = i < MOV_AXIS + esteppers ? tmp3[i] : def3[i < COUNT(def3) ? i : COUNT(def3) - 1];
}
EEPROM_READ(planner.acceleration);
@ -1165,6 +1207,19 @@ void MarlinSettings::postprocess() {
EEPROM_READ(delta_calibration_radius); // 1 float
EEPROM_READ(delta_tower_angle_trim); // 3 floats
#elif ENABLED(HANGPRINTER)
EEPROM_READ(anchor_A_y); // 1 float
EEPROM_READ(anchor_A_z); // 1 float
EEPROM_READ(anchor_B_x); // 1 float
EEPROM_READ(anchor_B_y); // 1 float
EEPROM_READ(anchor_B_z); // 1 float
EEPROM_READ(anchor_C_x); // 1 float
EEPROM_READ(anchor_C_y); // 1 float
EEPROM_READ(anchor_C_z); // 1 float
EEPROM_READ(anchor_D_z); // 1 float
EEPROM_READ(delta_segments_per_second); // 1 float
EEPROM_READ(dummy); // 1 float
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
_FIELD_TEST(x_endstop_adj);
@ -1714,8 +1769,9 @@ void MarlinSettings::postprocess() {
*/
void MarlinSettings::reset() {
static const float tmp1[] PROGMEM = DEFAULT_AXIS_STEPS_PER_UNIT, tmp2[] PROGMEM = DEFAULT_MAX_FEEDRATE;
static const uint32_t tmp3[] PROGMEM = DEFAULT_MAX_ACCELERATION;
LOOP_XYZE_N(i) {
LOOP_NUM_AXIS_N(i) {
planner.axis_steps_per_mm[i] = pgm_read_float(&tmp1[i < COUNT(tmp1) ? i : COUNT(tmp1) - 1]);
planner.max_feedrate_mm_s[i] = pgm_read_float(&tmp2[i < COUNT(tmp2) ? i : COUNT(tmp2) - 1]);
planner.max_acceleration_mm_per_s2[i] = pgm_read_dword_near(&tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]);
@ -1731,9 +1787,16 @@ void MarlinSettings::reset() {
#if ENABLED(JUNCTION_DEVIATION)
planner.junction_deviation_mm = float(JUNCTION_DEVIATION_MM);
#else
planner.max_jerk[X_AXIS] = DEFAULT_XJERK;
planner.max_jerk[Y_AXIS] = DEFAULT_YJERK;
planner.max_jerk[Z_AXIS] = DEFAULT_ZJERK;
#if ENABLED(HANGPRINTER)
planner.max_jerk[A_AXIS] = DEFAULT_AJERK;
planner.max_jerk[B_AXIS] = DEFAULT_BJERK;
planner.max_jerk[C_AXIS] = DEFAULT_CJERK;
planner.max_jerk[D_AXIS] = DEFAULT_DJERK;
#else
planner.max_jerk[X_AXIS] = DEFAULT_XJERK;
planner.max_jerk[Y_AXIS] = DEFAULT_YJERK;
planner.max_jerk[Z_AXIS] = DEFAULT_ZJERK;
#endif
planner.max_jerk[E_AXIS] = DEFAULT_EJERK;
#endif
@ -1785,6 +1848,19 @@ void MarlinSettings::reset() {
delta_calibration_radius = DELTA_CALIBRATION_RADIUS;
COPY(delta_tower_angle_trim, dta);
#elif ENABLED(HANGPRINTER)
anchor_A_y = float(ANCHOR_A_Y);
anchor_A_z = float(ANCHOR_A_Z);
anchor_B_x = float(ANCHOR_B_X);
anchor_B_y = float(ANCHOR_B_Y);
anchor_B_z = float(ANCHOR_B_Z);
anchor_C_x = float(ANCHOR_C_X);
anchor_C_y = float(ANCHOR_C_Y);
anchor_C_z = float(ANCHOR_C_Z);
anchor_D_z = float(ANCHOR_D_Z);
delta_segments_per_second = KINEMATIC_SEGMENTS_PER_SECOND;
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(X_DUAL_ENDSTOPS)
@ -1814,7 +1890,6 @@ void MarlinSettings::reset() {
#endif
);
#endif
#endif
#if ENABLED(ULTIPANEL)
@ -2038,9 +2113,16 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPGM("Steps per unit:");
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M92 X", LINEAR_UNIT(planner.axis_steps_per_mm[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.axis_steps_per_mm[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.axis_steps_per_mm[Z_AXIS]));
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(" M92 A", LINEAR_UNIT(planner.axis_steps_per_mm[A_AXIS]));
SERIAL_ECHOPAIR(" B", LINEAR_UNIT(planner.axis_steps_per_mm[B_AXIS]));
SERIAL_ECHOPAIR(" C", LINEAR_UNIT(planner.axis_steps_per_mm[C_AXIS]));
SERIAL_ECHOPAIR(" D", LINEAR_UNIT(planner.axis_steps_per_mm[D_AXIS]));
#else
SERIAL_ECHOPAIR(" M92 X", LINEAR_UNIT(planner.axis_steps_per_mm[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.axis_steps_per_mm[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.axis_steps_per_mm[Z_AXIS]));
#endif
#if DISABLED(DISTINCT_E_FACTORS)
SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.axis_steps_per_mm[E_AXIS]));
#endif
@ -2058,9 +2140,16 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPGM("Maximum feedrates (units/s):");
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M203 X", LINEAR_UNIT(planner.max_feedrate_mm_s[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_feedrate_mm_s[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_feedrate_mm_s[Z_AXIS]));
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(" M203 A", LINEAR_UNIT(planner.max_feedrate_mm_s[A_AXIS]));
SERIAL_ECHOPAIR(" B", LINEAR_UNIT(planner.max_feedrate_mm_s[B_AXIS]));
SERIAL_ECHOPAIR(" C", LINEAR_UNIT(planner.max_feedrate_mm_s[C_AXIS]));
SERIAL_ECHOPAIR(" D", LINEAR_UNIT(planner.max_feedrate_mm_s[D_AXIS]));
#else
SERIAL_ECHOPAIR(" M203 X", LINEAR_UNIT(planner.max_feedrate_mm_s[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_feedrate_mm_s[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_feedrate_mm_s[Z_AXIS]));
#endif
#if DISABLED(DISTINCT_E_FACTORS)
SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_feedrate_mm_s[E_AXIS]));
#endif
@ -2078,9 +2167,16 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPGM("Maximum Acceleration (units/s2):");
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M201 X", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[Z_AXIS]));
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(" M201 A", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[A_AXIS]));
SERIAL_ECHOPAIR(" B", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[B_AXIS]));
SERIAL_ECHOPAIR(" C", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[C_AXIS]));
SERIAL_ECHOPAIR(" D", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[D_AXIS]));
#else
SERIAL_ECHOPAIR(" M201 X", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_acceleration_mm_per_s2[Z_AXIS]));
#endif
#if DISABLED(DISTINCT_E_FACTORS)
SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_acceleration_mm_per_s2[E_AXIS]));
#endif
@ -2104,11 +2200,15 @@ void MarlinSettings::reset() {
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOPGM("Advanced: B<min_segment_time_us> S<min_feedrate> T<min_travel_feedrate>");
SERIAL_ECHOPGM("Advanced: Q<min_segment_time_us> S<min_feedrate> T<min_travel_feedrate>");
#if ENABLED(JUNCTION_DEVIATION)
SERIAL_ECHOPGM(" J<junc_dev>");
#else
SERIAL_ECHOPGM(" X<max_x_jerk> Y<max_y_jerk> Z<max_z_jerk>");
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPGM(" A<max_a_jerk> B<max_b_jerk> C<max_c_jerk> D<max_d_jerk>");
#else
SERIAL_ECHOPGM(" X<max_x_jerk> Y<max_y_jerk> Z<max_z_jerk>");
#endif
#endif
#if DISABLED(JUNCTION_DEVIATION) || ENABLED(LIN_ADVANCE)
SERIAL_ECHOPGM(" E<max_e_jerk>");
@ -2116,19 +2216,25 @@ void MarlinSettings::reset() {
SERIAL_EOL();
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M205 B", LINEAR_UNIT(planner.min_segment_time_us));
SERIAL_ECHOPAIR(" M205 Q", LINEAR_UNIT(planner.min_segment_time_us));
SERIAL_ECHOPAIR(" S", LINEAR_UNIT(planner.min_feedrate_mm_s));
SERIAL_ECHOPAIR(" T", LINEAR_UNIT(planner.min_travel_feedrate_mm_s));
#if ENABLED(JUNCTION_DEVIATION)
SERIAL_ECHOPAIR(" J", LINEAR_UNIT(planner.junction_deviation_mm));
#else
SERIAL_ECHOPAIR(" X", LINEAR_UNIT(planner.max_jerk[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_jerk[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_jerk[Z_AXIS]));
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(" A", LINEAR_UNIT(planner.max_jerk[A_AXIS]));
SERIAL_ECHOPAIR(" B", LINEAR_UNIT(planner.max_jerk[B_AXIS]));
SERIAL_ECHOPAIR(" C", LINEAR_UNIT(planner.max_jerk[C_AXIS]));
SERIAL_ECHOPAIR(" D", LINEAR_UNIT(planner.max_jerk[D_AXIS]));
#else
SERIAL_ECHOPAIR(" X", LINEAR_UNIT(planner.max_jerk[X_AXIS]));
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_jerk[Y_AXIS]));
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_jerk[Z_AXIS]));
#endif
SERIAL_ECHOPAIR(" E", LINEAR_UNIT(planner.max_jerk[E_AXIS]));
#endif
SERIAL_EOL();
#if HAS_M206_COMMAND
@ -2266,6 +2372,24 @@ void MarlinSettings::reset() {
SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(delta_tower_angle_trim[C_AXIS]));
SERIAL_EOL();
#elif ENABLED(HANGPRINTER)
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOLNPGM("Hangprinter settings: W<Ay> E<Az> R<Bx> T<By> Y<Bz> U<Cx> I<Cy> O<Cz> P<Dz> S<segments_per_s>");
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M665 W", anchor_A_y);
SERIAL_ECHOPAIR(" E", anchor_A_z);
SERIAL_ECHOPAIR(" R", anchor_B_x);
SERIAL_ECHOPAIR(" T", anchor_B_y);
SERIAL_ECHOPAIR(" Y", anchor_B_z);
SERIAL_ECHOPAIR(" U", anchor_C_x);
SERIAL_ECHOPAIR(" I", anchor_C_y);
SERIAL_ECHOPAIR(" O", anchor_C_z);
SERIAL_ECHOPAIR(" P", anchor_D_z);
SERIAL_ECHOPAIR(" S", delta_segments_per_second);
SERIAL_EOL();
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
if (!forReplay) {

View File

@ -39,10 +39,14 @@ enum AxisEnum : unsigned char {
B_AXIS = 1,
Z_AXIS = 2,
C_AXIS = 2,
E_AXIS = 3,
X_HEAD = 4,
Y_HEAD = 5,
Z_HEAD = 6,
E_CART = 3,
#if ENABLED(HANGPRINTER) // Hangprinter order: A_AXIS, B_AXIS, C_AXIS, D_AXIS, E_AXIS
D_AXIS = 3,
E_AXIS = 4,
#else
E_AXIS = 3,
#endif
X_HEAD, Y_HEAD, Z_HEAD,
ALL_AXES = 0xFE,
NO_AXIS = 0xFF
};
@ -54,11 +58,11 @@ enum AxisEnum : unsigned char {
#define LOOP_NA(VAR) LOOP_L_N(VAR, NUM_AXIS)
#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS)
#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS)
#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_CART)
#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N)
#define LOOP_ABC(VAR) LOOP_S_LE_N(VAR, A_AXIS, C_AXIS)
#define LOOP_ABCE(VAR) LOOP_S_LE_N(VAR, A_AXIS, E_AXIS)
#define LOOP_ABCE_N(VAR) LOOP_S_L_N(VAR, A_AXIS, XYZE_N)
#define LOOP_MOV_AXIS(VAR) LOOP_S_L_N(VAR, A_AXIS, MOV_AXIS)
#define LOOP_NUM_AXIS(VAR) LOOP_S_L_N(VAR, A_AXIS, NUM_AXIS)
#define LOOP_NUM_AXIS_N(VAR) LOOP_S_L_N(VAR, A_AXIS, NUM_AXIS_N)
typedef enum {
LINEARUNIT_MM,

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -123,7 +123,7 @@ void FWRetract::retract(const bool retracting
#endif
}
SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_CART]);
SERIAL_ECHOLNPAIR("hop_amount ", hop_amount);
//*/
@ -131,7 +131,7 @@ void FWRetract::retract(const bool retracting
renormalize = RECIPROCAL(planner.e_factor[active_extruder]),
base_retract = swapping ? swap_retract_length : retract_length,
old_z = current_position[Z_AXIS],
old_e = current_position[E_AXIS];
old_e = current_position[E_CART];
// The current position will be the destination for E and Z moves
set_destination_from_current();
@ -139,7 +139,7 @@ void FWRetract::retract(const bool retracting
if (retracting) {
// Retract by moving from a faux E position back to the current E position
feedrate_mm_s = retract_feedrate_mm_s;
destination[E_AXIS] -= base_retract * renormalize;
destination[E_CART] -= base_retract * renormalize;
prepare_move_to_destination(); // set_current_to_destination
// Is a Z hop set, and has the hop not yet been done?
@ -160,14 +160,14 @@ void FWRetract::retract(const bool retracting
hop_amount = 0.0; // Clear the hop amount
}
destination[E_AXIS] += (base_retract + (swapping ? swap_retract_recover_length : retract_recover_length)) * renormalize;
destination[E_CART] += (base_retract + (swapping ? swap_retract_recover_length : retract_recover_length)) * renormalize;
feedrate_mm_s = swapping ? swap_retract_recover_feedrate_mm_s : retract_recover_feedrate_mm_s;
prepare_move_to_destination(); // Recover E, set_current_to_destination
}
feedrate_mm_s = old_feedrate_mm_s; // Restore original feedrate
current_position[Z_AXIS] = old_z; // Restore Z and E positions
current_position[E_AXIS] = old_e;
current_position[E_CART] = old_e;
SYNC_PLAN_POSITION_KINEMATIC(); // As if the move never took place
retracted[active_extruder] = retracting; // Active extruder now retracted / recovered
@ -190,7 +190,7 @@ void FWRetract::retract(const bool retracting
#endif
}
SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_AXIS]);
SERIAL_ECHOLNPAIR("current_position[e] ", current_position[E_CART]);
SERIAL_ECHOLNPAIR("hop_amount ", hop_amount);
//*/

View File

@ -23,13 +23,18 @@
#ifndef MACROS_H
#define MACROS_H
#define NUM_AXIS 4
#define ABCE 4
#define XYZE 4
#define ABC 3
#define XYZ 3
#define XYZ 3
#define XYZE 4
#define ABC 3
#define ABCD 4
#define ABCE 4
#define ABCDE 5
// For use in macros that take a single axis letter
/**
* For use in macros that take a single axis letter
* The axis order in all axis related arrays is X, Y, Z, E
* For Hangprinter it is A, B, C, D, E
*/
#define _AXIS(A) (A##_AXIS)
#define _XMIN_ 100

View File

@ -696,6 +696,7 @@
// Dual X-carriage, Dual Y, Dual Z support
//
#define _D_PINS
#define _X2_PINS
#define _Y2_PINS
#define _Z2_PINS
@ -703,16 +704,64 @@
#define __EPIN(p,q) E##p##_##q##_PIN
#define _EPIN(p,q) __EPIN(p,q)
// The HANGPRINTER A, B, C, D axes
#if ENABLED(HANGPRINTER)
#define A_ENABLE_PIN X_ENABLE_PIN
#define A_DIR_PIN X_DIR_PIN
#define A_STEP_PIN X_STEP_PIN
#define A_MS1_PIN X_MS1_PIN
#define B_ENABLE_PIN Y_ENABLE_PIN
#define B_DIR_PIN Y_DIR_PIN
#define B_STEP_PIN Y_STEP_PIN
#define B_MS1_PIN Y_MS1_PIN
#define C_ENABLE_PIN Z_ENABLE_PIN
#define C_DIR_PIN Z_DIR_PIN
#define C_STEP_PIN Z_STEP_PIN
#define C_MS1_PIN Z_MS1_PIN
#ifndef D_STEP_PIN
#define D_STEP_PIN _EPIN(E_STEPPERS, STEP)
#define D_DIR_PIN _EPIN(E_STEPPERS, DIR)
#define D_ENABLE_PIN _EPIN(E_STEPPERS, ENABLE)
#ifndef D_CS_PIN
#define D_CS_PIN _EPIN(E_STEPPERS, CS)
#endif
#ifndef D_MS1_PIN
#define D_MS1_PIN _EPIN(E_STEPPERS, MS1)
#endif
#if E_STEPPERS >= MAX_EXTRUDERS || !PIN_EXISTS(D_ENABLE)
#error "No E stepper plug left for D Axis!"
#endif
#endif
#undef _D_PINS
#define ___D_PINS D_STEP_PIN, D_DIR_PIN, D_ENABLE_PIN,
#ifdef D_CS_PIN
#define __D_PINS ___D_PINS D_CS_PIN,
#else
#define __D_PINS ___D_PINS
#endif
#ifdef D_MS1_PIN
#define _D_PINS __D_PINS D_MS1_PIN,
#else
#define _D_PINS __D_PINS
#endif
#define X2_E_INDEX INCREMENT(E_STEPPERS)
#else
#define X2_E_INDEX E_STEPPERS
#endif
// The X2 axis, if any, should be the next open extruder port
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
#ifndef X2_STEP_PIN
#define X2_STEP_PIN _EPIN(E_STEPPERS, STEP)
#define X2_DIR_PIN _EPIN(E_STEPPERS, DIR)
#define X2_ENABLE_PIN _EPIN(E_STEPPERS, ENABLE)
#define X2_STEP_PIN _EPIN(X2_E_INDEX, STEP)
#define X2_DIR_PIN _EPIN(X2_E_INDEX, DIR)
#define X2_ENABLE_PIN _EPIN(X2_E_INDEX, ENABLE)
#ifndef X2_CS_PIN
#define X2_CS_PIN _EPIN(E_STEPPERS, CS)
#define X2_CS_PIN _EPIN(X2_E_INDEX, CS)
#endif
#if E_STEPPERS > 4 || !PIN_EXISTS(X2_ENABLE)
#if X2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(X2_ENABLE)
#error "No E stepper plug left for X2!"
#endif
#endif
@ -723,9 +772,9 @@
#else
#define _X2_PINS __X2_PINS
#endif
#define Y2_E_INDEX INCREMENT(E_STEPPERS)
#define Y2_E_INDEX INCREMENT(X2_E_INDEX)
#else
#define Y2_E_INDEX E_STEPPERS
#define Y2_E_INDEX X2_E_INDEX
#endif
// The Y2 axis, if any, should be the next open extruder port
@ -737,7 +786,7 @@
#ifndef Y2_CS_PIN
#define Y2_CS_PIN _EPIN(Y2_E_INDEX, CS)
#endif
#if Y2_E_INDEX > 4 || !PIN_EXISTS(Y2_ENABLE)
#if Y2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Y2_ENABLE)
#error "No E stepper plug left for Y2!"
#endif
#endif
@ -762,7 +811,7 @@
#ifndef Z2_CS_PIN
#define Z2_CS_PIN _EPIN(Z2_E_INDEX, CS)
#endif
#if Z2_E_INDEX > 4 || !PIN_EXISTS(Z2_ENABLE)
#if Z2_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z2_ENABLE)
#error "No E stepper plug left for Z2!"
#endif
#endif
@ -782,7 +831,7 @@
PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, FAN1_PIN, FAN2_PIN, CONTROLLER_FAN_PIN, \
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \
_H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \
_X2_PINS _Y2_PINS _Z2_PINS \
_D_PINS _X2_PINS _Y2_PINS _Z2_PINS \
}
#define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))

View File

@ -100,13 +100,13 @@ volatile uint8_t Planner::block_buffer_head, // Index of the next block to be
uint16_t Planner::cleaning_buffer_counter; // A counter to disable queuing of blocks
uint8_t Planner::delay_before_delivering; // This counter delays delivery of blocks when queue becomes empty to allow the opportunity of merging blocks
uint32_t Planner::max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE
Planner::max_acceleration_steps_per_s2[XYZE_N], // (steps/s^2) Derived from mm_per_s2
Planner::min_segment_time_us; // (µs) M205 B
uint32_t Planner::max_acceleration_mm_per_s2[NUM_AXIS_N], // (mm/s^2) M201 XYZE
Planner::max_acceleration_steps_per_s2[NUM_AXIS_N], // (steps/s^2) Derived from mm_per_s2
Planner::min_segment_time_us; // (µs) M205 Q
float Planner::max_feedrate_mm_s[XYZE_N], // (mm/s) M203 XYZE - Max speeds
Planner::axis_steps_per_mm[XYZE_N], // (steps) M92 XYZE - Steps per millimeter
Planner::steps_to_mm[XYZE_N], // (mm) Millimeters per step
float Planner::max_feedrate_mm_s[NUM_AXIS_N], // (mm/s) M203 XYZE - Max speeds
Planner::axis_steps_per_mm[NUM_AXIS_N], // (steps) M92 XYZE - Steps per millimeter
Planner::steps_to_mm[NUM_AXIS_N], // (mm) Millimeters per step
Planner::min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate
Planner::acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
Planner::retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
@ -123,7 +123,14 @@ float Planner::max_feedrate_mm_s[XYZE_N], // (mm/s) M203 XYZE - Max speeds
#endif
#endif
#else
float Planner::max_jerk[XYZE]; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
float Planner::max_jerk[NUM_AXIS]; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
#endif
#if ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
float Planner::k0[MOV_AXIS],
Planner::k1[MOV_AXIS],
Planner::k2[MOV_AXIS],
Planner::sqrtk1[MOV_AXIS];
#endif
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
@ -206,7 +213,7 @@ float Planner::previous_speed[NUM_AXIS],
#endif
#if HAS_POSITION_FLOAT
float Planner::position_float[XYZE]; // Needed for accurate maths. Steps cannot be used!
float Planner::position_float[NUM_AXIS]; // Needed for accurate maths. Steps cannot be used!
#endif
#if ENABLED(ULTRA_LCD)
@ -1137,7 +1144,13 @@ void Planner::recalculate() {
float high = 0.0;
for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) {
block_t* block = &block_buffer[b];
if (block->steps[X_AXIS] || block->steps[Y_AXIS] || block->steps[Z_AXIS]) {
if (
#if ENABLED(HANGPRINTER)
block->steps[A_AXIS] || block->steps[B_AXIS] || block->steps[C_AXIS] || block->steps[D_AXIS]
#else
block->steps[X_AXIS] || block->steps[Y_AXIS] || block->steps[Z_AXIS]
#endif
) {
const float se = (float)block->steps[E_AXIS] / block->step_event_count * SQRT(block->nominal_speed_sqr); // mm/sec;
NOLESS(high, se);
}
@ -1514,6 +1527,9 @@ float Planner::get_axis_position_mm(const AxisEnum axis) {
#else
axis_steps = stepper.position(axis);
#endif
#if ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
if (axis != E_AXIS) return (sq(axis_steps / k0[axis] + sqrtk1[axis]) - k1[axis]) / k2[axis];
#endif
return axis_steps * steps_to_mm[axis];
}
@ -1522,23 +1538,34 @@ float Planner::get_axis_position_mm(const AxisEnum axis) {
*/
void Planner::synchronize() { while (has_blocks_queued() || cleaning_buffer_counter) idle(); }
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
#define COUNT_MOVE count_it
#else
#define COUNT_MOVE true
#endif
/**
* Planner::_buffer_steps
*
* Add a new linear movement to the planner queue (in terms of steps).
*
* target - target position in steps units
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* target - target position in steps units
* target_float - target position in mm (HAS_POSITION_FLOAT)
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* count_it - apply this move to the counters (UNREGISTERED_MOVE_SUPPORT)
*
* Returns true if movement was properly queued, false otherwise
*/
bool Planner::_buffer_steps(const int32_t (&target)[XYZE]
bool Planner::_buffer_steps(const int32_t (&target)[NUM_AXIS]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
, const float (&target_float)[NUM_AXIS]
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, const bool count_it/*=true*/
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters
) {
// If we are cleaning, do not accept queuing of movements
@ -1554,6 +1581,9 @@ bool Planner::_buffer_steps(const int32_t (&target)[XYZE]
, target_float
#endif
, fr_mm_s, extruder, millimeters
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, count_it
#endif
)) {
// Movement was not queued, probably because it was too short.
// Simply accept that as movement queued and done
@ -1585,24 +1615,33 @@ bool Planner::_buffer_steps(const int32_t (&target)[XYZE]
*
* Fills a new linear movement in the block (in terms of steps).
*
* target - target position in steps units
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* target - target position in steps units
* target_float - target position in mm (HAS_POSITION_FLOAT)
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* count_it - apply this move to the counters (UNREGISTERED_MOVE_SUPPORT)
*
* Returns true is movement is acceptable, false otherwise
*/
bool Planner::_populate_block(block_t * const block, bool split_move,
const int32_t (&target)[XYZE]
const int32_t (&target)[NUM_AXIS]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
, const float (&target_float)[NUM_AXIS]
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, const bool count_it/*=true*/
#endif
) {
const int32_t da = target[A_AXIS] - position[A_AXIS],
db = target[B_AXIS] - position[B_AXIS],
dc = target[C_AXIS] - position[C_AXIS];
dc = target[C_AXIS] - position[C_AXIS]
#if ENABLED(HANGPRINTER)
, dd = target[D_AXIS] - position[D_AXIS]
#endif
;
int32_t de = target[E_AXIS] - position[E_AXIS];
/* <-- add a slash to enable
@ -1622,10 +1661,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
if (de) {
#if ENABLED(PREVENT_COLD_EXTRUSION)
if (thermalManager.tooColdToExtrude(extruder)) {
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS];
#endif
if (COUNT_MOVE) {
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS];
#endif
}
de = 0; // no difference
SERIAL_ECHO_START();
SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
@ -1633,10 +1674,12 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#endif // PREVENT_COLD_EXTRUSION
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
if (ABS(de * e_factor[extruder]) > (int32_t)axis_steps_per_mm[E_AXIS_N] * (EXTRUDE_MAXLENGTH)) { // It's not important to get max. extrusion length in a precision < 1mm, so save some cycles and cast to int
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS];
#endif
if (COUNT_MOVE) {
position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = target_float[E_AXIS];
#endif
}
de = 0; // no difference
SERIAL_ECHO_START();
SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
@ -1665,6 +1708,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
if (dc < 0) SBI(dm, Z_HEAD); // ...and Z
if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction
if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction
#elif ENABLED(HANGPRINTER)
if (da < 0) SBI(dm, A_AXIS);
if (db < 0) SBI(dm, B_AXIS);
if (dc < 0) SBI(dm, C_AXIS);
if (dd < 0) SBI(dm, D_AXIS);
#else
if (da < 0) SBI(dm, X_AXIS);
if (db < 0) SBI(dm, Y_AXIS);
@ -1681,6 +1729,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Set direction bits
block->direction_bits = dm;
// Specify if block is to be counted or not
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
block->count_it = count_it;
#endif
// Number of steps for each axis
// See http://www.corexy.com/theory.html
#if CORE_IS_XY
@ -1699,6 +1752,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = ABS(db);
block->steps[Z_AXIS] = ABS(dc);
#elif ENABLED(HANGPRINTER)
block->steps[A_AXIS] = ABS(da);
block->steps[B_AXIS] = ABS(db);
block->steps[C_AXIS] = ABS(dc);
block->steps[D_AXIS] = ABS(dd);
#else
// default non-h-bot planning
block->steps[A_AXIS] = ABS(da);
@ -1707,7 +1765,14 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
#endif
block->steps[E_AXIS] = esteps;
block->step_event_count = MAX4(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps);
block->step_event_count = (
#if ENABLED(HANGPRINTER)
MAX5(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], block->steps[D_AXIS], esteps)
#else
MAX4(block->steps[A_AXIS], block->steps[B_AXIS], block->steps[C_AXIS], esteps)
#endif
);
// Bail if this is a zero-length block
if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return false;
@ -1761,7 +1826,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
enable_Z();
}
if (block->steps[X_AXIS]) enable_X();
#else
#elif DISABLED(HANGPRINTER) // Hangprinters X, Y, Z, E0 axes should always be enabled anyways
if (block->steps[X_AXIS]) enable_X();
if (block->steps[Y_AXIS]) enable_Y();
#if DISABLED(Z_LATE_ENABLE)
@ -1902,14 +1967,21 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
delta_mm[C_AXIS] = CORESIGN(db - dc) * steps_to_mm[C_AXIS];
#endif
#else
float delta_mm[ABCE];
float delta_mm[NUM_AXIS];
delta_mm[A_AXIS] = da * steps_to_mm[A_AXIS];
delta_mm[B_AXIS] = db * steps_to_mm[B_AXIS];
delta_mm[C_AXIS] = dc * steps_to_mm[C_AXIS];
#if ENABLED(HANGPRINTER)
delta_mm[D_AXIS] = dd * steps_to_mm[D_AXIS];
#endif
#endif
delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N];
if (block->steps[A_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[B_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[C_AXIS] < MIN_STEPS_PER_SEGMENT) {
if (block->steps[A_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[B_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[C_AXIS] < MIN_STEPS_PER_SEGMENT
#if ENABLED(HANGPRINTER)
&& block->steps[D_AXIS] < MIN_STEPS_PER_SEGMENT
#endif
) {
block->millimeters = ABS(delta_mm[E_AXIS]);
}
else if (!millimeters) {
@ -1920,6 +1992,8 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_HEAD])
#elif CORE_IS_YZ
sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_HEAD])
#elif ENABLED(HANGPRINTER)
sq(delta_mm[A_AXIS]) + sq(delta_mm[B_AXIS]) + sq(delta_mm[C_AXIS]) + sq(delta_mm[D_AXIS])
#else
sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_AXIS])
#endif
@ -2005,7 +2079,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Calculate and limit speed in mm/sec for each axis
float current_speed[NUM_AXIS], speed_factor = 1.0f; // factor <1 decreases speed
LOOP_XYZE(i) {
LOOP_NUM_AXIS(i) {
const float cs = ABS((current_speed[i] = delta_mm[i] * inverse_secs));
#if ENABLED(DISTINCT_E_FACTORS)
if (i == E_AXIS) i += extruder;
@ -2053,7 +2127,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Correct the speed
if (speed_factor < 1.0f) {
LOOP_XYZE(i) current_speed[i] *= speed_factor;
LOOP_NUM_AXIS(i) current_speed[i] *= speed_factor;
block->nominal_rate *= speed_factor;
block->nominal_speed_sqr = block->nominal_speed_sqr * sq(speed_factor);
}
@ -2061,7 +2135,11 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Compute and limit the acceleration rate for the trapezoid generator.
const float steps_per_mm = block->step_event_count * inverse_millimeters;
uint32_t accel;
if (!block->steps[A_AXIS] && !block->steps[B_AXIS] && !block->steps[C_AXIS]) {
if (!block->steps[A_AXIS] && !block->steps[B_AXIS] && !block->steps[C_AXIS]
#if ENABLED(HANGPRINTER)
&& !block->steps[D_AXIS]
#endif
) {
// convert to: acceleration steps/sec^2
accel = CEIL(retract_acceleration * steps_per_mm);
#if ENABLED(LIN_ADVANCE)
@ -2148,12 +2226,18 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
LIMIT_ACCEL_LONG(A_AXIS, 0);
LIMIT_ACCEL_LONG(B_AXIS, 0);
LIMIT_ACCEL_LONG(C_AXIS, 0);
#if ENABLED(HANGPRINTER)
LIMIT_ACCEL_LONG(D_AXIS, 0);
#endif
LIMIT_ACCEL_LONG(E_AXIS, ACCEL_IDX);
}
else {
LIMIT_ACCEL_FLOAT(A_AXIS, 0);
LIMIT_ACCEL_FLOAT(B_AXIS, 0);
LIMIT_ACCEL_FLOAT(C_AXIS, 0);
#if ENABLED(HANGPRINTER)
LIMIT_ACCEL_FLOAT(D_AXIS, 0);
#endif
LIMIT_ACCEL_FLOAT(E_AXIS, ACCEL_IDX);
}
}
@ -2289,7 +2373,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
float safe_speed = nominal_speed;
uint8_t limited = 0;
LOOP_XYZE(i) {
LOOP_NUM_AXIS(i) {
const float jerk = ABS(current_speed[i]), // cs : Starting from zero, change in speed for this axis
maxj = max_jerk[i]; // mj : The max jerk setting for this axis
if (jerk > maxj) { // cs > mj : New current speed too fast?
@ -2321,7 +2405,7 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
// Now limit the jerk in all axes.
const float smaller_speed_factor = vmax_junction / previous_nominal_speed;
LOOP_XYZE(axis) {
LOOP_NUM_AXIS(axis) {
// Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop.
float v_exit = previous_speed[axis] * smaller_speed_factor,
v_entry = current_speed[axis];
@ -2381,12 +2465,22 @@ bool Planner::_populate_block(block_t * const block, bool split_move,
COPY(previous_speed, current_speed);
previous_nominal_speed_sqr = block->nominal_speed_sqr;
// Update the position
static_assert(COUNT(target) > 1, "Parameter to _buffer_steps must be (&target)[XYZE]!");
COPY(position, target);
#if HAS_POSITION_FLOAT
COPY(position_float, target_float);
#endif
// Update the position (only when a move was queued)
static_assert(COUNT(target) > 1, "Parameter to _populate_block must be (&target)["
#if ENABLED(HANGPRINTER)
"ABCD"
#else
"XYZ"
#endif
"E]!"
);
if (COUNT_MOVE) {
COPY(position, target);
#if HAS_POSITION_FLOAT
COPY(position_float, target_float);
#endif
}
// Movement was accepted
return true;
@ -2409,6 +2503,9 @@ void Planner::buffer_sync_block() {
block->position[A_AXIS] = position[A_AXIS];
block->position[B_AXIS] = position[B_AXIS];
block->position[C_AXIS] = position[C_AXIS];
#if ENABLED(HANGPRINTER)
block->position[D_AXIS] = position[D_AXIS];
#endif
block->position[E_AXIS] = position[E_AXIS];
// If this is the first added movement, reload the delay, otherwise, cancel it.
@ -2438,7 +2535,15 @@ void Planner::buffer_sync_block() {
* extruder - target extruder
* millimeters - the length of the movement, if known
*/
bool Planner::buffer_segment(const float &a, const float &b, const float &c, const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/) {
bool Planner::buffer_segment(const float &a, const float &b, const float &c
#if ENABLED(HANGPRINTER)
, const float &d
#endif
, const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters/*=0.0*/
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, bool count_it /* = true */
#endif
) {
// If we are cleaning, do not accept queuing of movements
if (cleaning_buffer_counter) return false;
@ -2453,23 +2558,40 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con
// The target position of the tool in absolute steps
// Calculate target position in absolute steps
const int32_t target[ABCE] = {
LROUND(a * axis_steps_per_mm[A_AXIS]),
LROUND(b * axis_steps_per_mm[B_AXIS]),
LROUND(c * axis_steps_per_mm[C_AXIS]),
const int32_t target[NUM_AXIS] = {
#if ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
LROUND(k0[A_AXIS] * (SQRT(k1[A_AXIS] + a * k2[A_AXIS]) - sqrtk1[A_AXIS])),
LROUND(k0[B_AXIS] * (SQRT(k1[B_AXIS] + b * k2[B_AXIS]) - sqrtk1[B_AXIS])),
LROUND(k0[C_AXIS] * (SQRT(k1[C_AXIS] + c * k2[C_AXIS]) - sqrtk1[C_AXIS])),
LROUND(k0[D_AXIS] * (SQRT(k1[D_AXIS] + d * k2[D_AXIS]) - sqrtk1[D_AXIS])),
#else
LROUND(a * axis_steps_per_mm[A_AXIS]),
LROUND(b * axis_steps_per_mm[B_AXIS]),
LROUND(c * axis_steps_per_mm[C_AXIS]),
#if ENABLED(HANGPRINTER)
LROUND(d * axis_steps_per_mm[D_AXIS]),
#endif
#endif
LROUND(e * axis_steps_per_mm[E_AXIS_N])
};
#if HAS_POSITION_FLOAT
const float target_float[XYZE] = { a, b, c, e };
const float target_float[NUM_AXIS] = { a, b, c
#if ENABLED(HANGPRINTER)
, d
#endif
, e
};
#endif
// DRYRUN prevents E moves from taking place
if (DEBUGGING(DRYRUN)) {
position[E_AXIS] = target[E_AXIS];
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = e;
#endif
if (COUNT_MOVE) {
position[E_AXIS] = target[E_AXIS];
#if HAS_POSITION_FLOAT
position_float[E_AXIS] = e;
#endif
}
}
/* <-- add a slash to enable
@ -2487,13 +2609,18 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con
#endif
SERIAL_ECHOPAIR(" (", position[Y_AXIS]);
SERIAL_ECHOPAIR("->", target[Y_AXIS]);
#if ENABLED(DELTA)
#if ENABLED(DELTA) || ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(") C:", c);
#else
SERIAL_ECHOPAIR(") Z:", c);
#endif
SERIAL_ECHOPAIR(" (", position[Z_AXIS]);
SERIAL_ECHOPAIR("->", target[Z_AXIS]);
#if ENABLED(HANGPRINTER)
SERIAL_ECHOPAIR(") D:", d);
SERIAL_ECHOPAIR(" (", position[D_AXIS]);
SERIAL_ECHOPAIR("->", target[D_AXIS]);
#endif
SERIAL_ECHOPAIR(") E:", e);
SERIAL_ECHOPAIR(" (", position[E_AXIS]);
SERIAL_ECHOPAIR("->", target[E_AXIS]);
@ -2501,12 +2628,15 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con
//*/
// Queue the movement
if (
if (
!_buffer_steps(target
#if HAS_POSITION_FLOAT
, target_float
#endif
, fr_mm_s, extruder, millimeters
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, count_it
#endif
)
) return false;
@ -2521,23 +2651,41 @@ bool Planner::buffer_segment(const float &a, const float &b, const float &c, con
* On CORE machines stepper ABC will be translated from the given XYZ.
*/
void Planner::_set_position_mm(const float &a, const float &b, const float &c, const float &e) {
void Planner::_set_position_mm(const float &a, const float &b, const float &c
#if ENABLED(HANGPRINTER)
, const float &d
#endif
, const float &e
) {
#if ENABLED(DISTINCT_E_FACTORS)
last_extruder = active_extruder;
#endif
position[A_AXIS] = LROUND(a * axis_steps_per_mm[A_AXIS]);
position[B_AXIS] = LROUND(b * axis_steps_per_mm[B_AXIS]);
position[C_AXIS] = LROUND(axis_steps_per_mm[C_AXIS] * (c + (
#if !IS_KINEMATIC && ENABLED(AUTO_BED_LEVELING_UBL)
leveling_active ? ubl.get_z_correction(a, b) :
#if ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
position[A_AXIS] = LROUND(k0[A_AXIS] * (SQRT(k1[A_AXIS] + a * k2[A_AXIS]) - sqrtk1[A_AXIS])),
position[B_AXIS] = LROUND(k0[B_AXIS] * (SQRT(k1[B_AXIS] + b * k2[B_AXIS]) - sqrtk1[B_AXIS])),
position[C_AXIS] = LROUND(k0[C_AXIS] * (SQRT(k1[C_AXIS] + c * k2[C_AXIS]) - sqrtk1[C_AXIS])),
position[D_AXIS] = LROUND(k0[D_AXIS] * (SQRT(k1[D_AXIS] + d * k2[D_AXIS]) - sqrtk1[D_AXIS])),
#else
position[A_AXIS] = LROUND(a * axis_steps_per_mm[A_AXIS]);
position[B_AXIS] = LROUND(b * axis_steps_per_mm[B_AXIS]);
position[C_AXIS] = LROUND(axis_steps_per_mm[C_AXIS] * (c + (
#if !IS_KINEMATIC && ENABLED(AUTO_BED_LEVELING_UBL)
leveling_active ? ubl.get_z_correction(a, b) :
#endif
0)
));
#if ENABLED(HANGPRINTER)
position[D_AXIS] = LROUND(d * axis_steps_per_mm[D_AXIS]),
#endif
0
)));
#endif
position[E_AXIS] = LROUND(e * axis_steps_per_mm[_EINDEX]);
#if HAS_POSITION_FLOAT
position_float[A_AXIS] = a;
position_float[B_AXIS] = b;
position_float[C_AXIS] = c;
#if ENABLED(HANGPRINTER)
position_float[D_AXIS] = d;
#endif
position_float[E_AXIS] = e;
#endif
if (has_blocks_queued()) {
@ -2546,21 +2694,32 @@ void Planner::_set_position_mm(const float &a, const float &b, const float &c, c
buffer_sync_block();
}
else
stepper.set_position(position[A_AXIS], position[B_AXIS], position[C_AXIS], position[E_AXIS]);
stepper.set_position(position[A_AXIS], position[B_AXIS], position[C_AXIS],
#if ENABLED(HANGPRINTER)
position[D_AXIS],
#endif
position[E_AXIS]
);
}
void Planner::set_position_mm_kinematic(const float (&cart)[XYZE]) {
#if PLANNER_LEVELING
float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] };
apply_leveling(raw);
#elif ENABLED(HANGPRINTER)
float raw[XYZ] = { cart[X_AXIS], cart[Y_AXIS], cart[Z_AXIS] };
#else
const float (&raw)[XYZE] = cart;
#endif
#if IS_KINEMATIC
inverse_kinematics(raw);
_set_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_AXIS]);
#if ENABLED(HANGPRINTER)
_set_position_mm(line_lengths[A_AXIS], line_lengths[B_AXIS], line_lengths[C_AXIS], line_lengths[D_AXIS], cart[E_CART]);
#else
_set_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_CART]);
#endif
#else
_set_position_mm(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_AXIS]);
_set_position_mm(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_CART]);
#endif
}
@ -2597,7 +2756,7 @@ void Planner::reset_acceleration_rates() {
#define AXIS_CONDITION true
#endif
uint32_t highest_rate = 1;
LOOP_XYZE_N(i) {
LOOP_NUM_AXIS_N(i) {
max_acceleration_steps_per_s2[i] = max_acceleration_mm_per_s2[i] * axis_steps_per_mm[i];
if (AXIS_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]);
}
@ -2609,7 +2768,7 @@ void Planner::reset_acceleration_rates() {
// Recalculate position, steps_to_mm if axis_steps_per_mm changes!
void Planner::refresh_positioning() {
LOOP_XYZE_N(i) steps_to_mm[i] = 1.0f / axis_steps_per_mm[i];
LOOP_NUM_AXIS_N(i) steps_to_mm[i] = 1.0f / axis_steps_per_mm[i];
set_position_mm_kinematic(current_position);
reset_acceleration_rates();
}

View File

@ -76,6 +76,10 @@ typedef struct {
volatile uint8_t flag; // Block flags (See BlockFlag enum above) - Modified by ISR and main thread!
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
bool count_it;
#endif
// Fields used by the motion planner to manage acceleration
float nominal_speed_sqr, // The nominal speed for this block in (mm/sec)^2
entry_speed_sqr, // Entry speed at previous-current junction in (mm/sec)^2
@ -188,12 +192,12 @@ class Planner {
// May be auto-adjusted by a filament width sensor
#endif
static uint32_t max_acceleration_mm_per_s2[XYZE_N], // (mm/s^2) M201 XYZE
max_acceleration_steps_per_s2[XYZE_N], // (steps/s^2) Derived from mm_per_s2
min_segment_time_us; // (µs) M205 B
static float max_feedrate_mm_s[XYZE_N], // (mm/s) M203 XYZE - Max speeds
axis_steps_per_mm[XYZE_N], // (steps) M92 XYZE - Steps per millimeter
steps_to_mm[XYZE_N], // (mm) Millimeters per step
static uint32_t max_acceleration_mm_per_s2[NUM_AXIS_N], // (mm/s^2) M201 XYZE
max_acceleration_steps_per_s2[NUM_AXIS_N], // (steps/s^2) Derived from mm_per_s2
min_segment_time_us; // (µs) M205 Q
static float max_feedrate_mm_s[NUM_AXIS_N], // (mm/s) M203 XYZE - Max speeds
axis_steps_per_mm[NUM_AXIS_N], // (steps) M92 XYZE - Steps per millimeter
steps_to_mm[NUM_AXIS_N], // (mm) Millimeters per step
min_feedrate_mm_s, // (mm/s) M205 S - Minimum linear feedrate
acceleration, // (mm/s^2) M204 S - Normal acceleration. DEFAULT ACCELERATION for all printing moves.
retract_acceleration, // (mm/s^2) M204 R - Retract acceleration. Filament pull-back and push-forward while standing still in the other axes
@ -210,7 +214,19 @@ class Planner {
#endif
#endif
#else
static float max_jerk[XYZE]; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
static float max_jerk[NUM_AXIS]; // (mm/s^2) M205 XYZE - The largest speed change requiring no acceleration.
#endif
#if ENABLED(LINE_BUILDUP_COMPENSATION_FEATURE)
/*
* Parameters for calculating target[]
* See buildup compensation theory:
* https://vitana.se/opr3d/tbear/2017.html#hangprinter_project_29
*/
static float k0[MOV_AXIS],
k1[MOV_AXIS],
k2[MOV_AXIS],
sqrtk1[MOV_AXIS];
#endif
#if HAS_LEVELING
@ -230,7 +246,7 @@ class Planner {
#endif
#if HAS_POSITION_FLOAT
static float position_float[XYZE];
static float position_float[NUM_AXIS];
#endif
#if ENABLED(SKEW_CORRECTION)
@ -429,11 +445,17 @@ class Planner {
#define ARG_X float rx
#define ARG_Y float ry
#define ARG_Z float rz
#if ENABLED(HANGPRINTER)
#define ARG_E1 float re1
#endif
static void unapply_leveling(float raw[XYZ]);
#else
#define ARG_X const float &rx
#define ARG_Y const float &ry
#define ARG_Z const float &rz
#if ENABLED(HANGPRINTER)
#define ARG_E1 const float &re1
#endif
#endif
// Number of moves currently in the planner including the busy block, if any
@ -477,14 +499,18 @@ class Planner {
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* count_it - apply this move to the counters (UNREGISTERED_MOVE_SUPPORT)
*
* Returns true if movement was buffered, false otherwise
*/
static bool _buffer_steps(const int32_t (&target)[XYZE]
static bool _buffer_steps(const int32_t (&target)[NUM_AXIS]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
, const float (&target_float)[NUM_AXIS]
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters=0.0
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, const bool count_it=true
#endif
);
/**
@ -496,15 +522,19 @@ class Planner {
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* count_it - apply this move to the counters (UNREGISTERED_MOVE_SUPPORT)
*
* Returns true is movement is acceptable, false otherwise
*/
static bool _populate_block(block_t * const block, bool split_move,
const int32_t (&target)[XYZE]
const int32_t (&target)[NUM_AXIS]
#if HAS_POSITION_FLOAT
, const float (&target_float)[XYZE]
, const float (&target_float)[NUM_AXIS]
#endif
, float fr_mm_s, const uint8_t extruder, const float &millimeters=0.0
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, const bool count_it=true
#endif
);
/**
@ -521,13 +551,28 @@ class Planner {
* Leveling and kinematics should be applied ahead of calling this.
*
* a,b,c,e - target positions in mm and/or degrees
* (a, b, c, d, e for Hangprinter)
* fr_mm_s - (target) speed of the move
* extruder - target extruder
* millimeters - the length of the movement, if known
* count_it - remember this move in its counters (UNREGISTERED_MOVE_SUPPORT)
*/
static bool buffer_segment(const float &a, const float &b, const float &c, const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0);
static bool buffer_segment(const float &a, const float &b, const float &c,
#if ENABLED(HANGPRINTER)
const float &d,
#endif
const float &e, const float &fr_mm_s, const uint8_t extruder, const float &millimeters=0.0
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
, bool count_it=true
#endif
);
static void _set_position_mm(const float &a, const float &b, const float &c, const float &e);
static void _set_position_mm(const float &a, const float &b, const float &c,
#if ENABLED(HANGPRINTER)
const float &d,
#endif
const float &e
);
/**
* Add a new linear movement to the buffer.
@ -538,15 +583,26 @@ class Planner {
* (Cartesians may also call buffer_line_kinematic.)
*
* rx,ry,rz,e - target position in mm or degrees
* (rx, ry, rz, re1 for Hangprinter)
* fr_mm_s - (target) speed of the move (mm/s)
* extruder - target extruder
* millimeters - the length of the movement, if known
*/
FORCE_INLINE static bool buffer_line(ARG_X, ARG_Y, ARG_Z, const float &e, const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0) {
FORCE_INLINE static bool buffer_line(ARG_X, ARG_Y, ARG_Z,
#if ENABLED(HANGPRINTER)
ARG_E1,
#endif
const float &e, const float &fr_mm_s, const uint8_t extruder, const float millimeters = 0.0
) {
#if PLANNER_LEVELING && IS_CARTESIAN
apply_leveling(rx, ry, rz);
#endif
return buffer_segment(rx, ry, rz, e, fr_mm_s, extruder, millimeters);
return buffer_segment(rx, ry, rz,
#if ENABLED(HANGPRINTER)
re1,
#endif
e, fr_mm_s, extruder, millimeters
);
}
/**
@ -568,9 +624,16 @@ class Planner {
#endif
#if IS_KINEMATIC
inverse_kinematics(raw);
return buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
return buffer_segment(
#if ENABLED(HANGPRINTER)
line_lengths[A_AXIS], line_lengths[B_AXIS], line_lengths[C_AXIS], line_lengths[D_AXIS]
#else
delta[A_AXIS], delta[B_AXIS], delta[C_AXIS]
#endif
, cart[E_CART], fr_mm_s, extruder, millimeters
);
#else
return buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_AXIS], fr_mm_s, extruder, millimeters);
return buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], cart[E_CART], fr_mm_s, extruder, millimeters);
#endif
}
@ -583,11 +646,21 @@ class Planner {
*
* Clears previous speed values.
*/
FORCE_INLINE static void set_position_mm(ARG_X, ARG_Y, ARG_Z, const float &e) {
FORCE_INLINE static void set_position_mm(ARG_X, ARG_Y, ARG_Z,
#if ENABLED(HANGPRINTER)
ARG_E1,
#endif
const float &e
) {
#if PLANNER_LEVELING && IS_CARTESIAN
apply_leveling(rx, ry, rz);
#endif
_set_position_mm(rx, ry, rz, e);
_set_position_mm(rx, ry, rz,
#if ENABLED(HANGPRINTER)
re1,
#endif
e
);
}
static void set_position_mm_kinematic(const float (&cart)[XYZE]);
static void set_position_mm(const AxisEnum axis, const float &v);

View File

@ -105,17 +105,17 @@ inline static float dist1(float x1, float y1, float x2, float y2) { return ABS(x
* the mitigation offered by MIN_STEP and the small computational
* power available on Arduino, I think it is not wise to implement it.
*/
void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS], const float offset[4], float fr_mm_s, uint8_t extruder) {
void cubic_b_spline(const float pos[XYZE], const float cart_target[XYZE], const float offset[4], float fr_mm_s, uint8_t extruder) {
// Absolute first and second control points are recovered.
const float first0 = position[X_AXIS] + offset[0],
first1 = position[Y_AXIS] + offset[1],
second0 = target[X_AXIS] + offset[2],
second1 = target[Y_AXIS] + offset[3];
const float first0 = pos[X_AXIS] + offset[0],
first1 = pos[Y_AXIS] + offset[1],
second0 = cart_target[X_AXIS] + offset[2],
second1 = cart_target[Y_AXIS] + offset[3];
float t = 0;
float bez_target[4];
bez_target[X_AXIS] = position[X_AXIS];
bez_target[Y_AXIS] = position[Y_AXIS];
float bez_target[XYZE];
bez_target[X_AXIS] = pos[X_AXIS];
bez_target[Y_AXIS] = pos[Y_AXIS];
float step = MAX_STEP;
millis_t next_idle_ms = millis() + 200UL;
@ -134,13 +134,13 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
bool did_reduce = false;
float new_t = t + step;
NOMORE(new_t, 1);
float new_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], new_t),
new_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], new_t);
float new_pos0 = eval_bezier(pos[X_AXIS], first0, second0, cart_target[X_AXIS], new_t),
new_pos1 = eval_bezier(pos[Y_AXIS], first1, second1, cart_target[Y_AXIS], new_t);
for (;;) {
if (new_t - t < (MIN_STEP)) break;
const float candidate_t = 0.5f * (t + new_t),
candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
candidate_pos0 = eval_bezier(pos[X_AXIS], first0, second0, cart_target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(pos[Y_AXIS], first1, second1, cart_target[Y_AXIS], candidate_t),
interp_pos0 = 0.5f * (bez_target[X_AXIS] + new_pos0),
interp_pos1 = 0.5f * (bez_target[Y_AXIS] + new_pos1);
if (dist1(candidate_pos0, candidate_pos1, interp_pos0, interp_pos1) <= (SIGMA)) break;
@ -155,8 +155,8 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
if (new_t - t > MAX_STEP) break;
const float candidate_t = t + 2 * (new_t - t);
if (candidate_t >= 1) break;
const float candidate_pos0 = eval_bezier(position[X_AXIS], first0, second0, target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(position[Y_AXIS], first1, second1, target[Y_AXIS], candidate_t),
const float candidate_pos0 = eval_bezier(pos[X_AXIS], first0, second0, cart_target[X_AXIS], candidate_t),
candidate_pos1 = eval_bezier(pos[Y_AXIS], first1, second1, cart_target[Y_AXIS], candidate_t),
interp_pos0 = 0.5f * (bez_target[X_AXIS] + candidate_pos0),
interp_pos1 = 0.5f * (bez_target[Y_AXIS] + candidate_pos1);
if (dist1(new_pos0, new_pos1, interp_pos0, interp_pos1) > (SIGMA)) break;
@ -184,14 +184,14 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS]
bez_target[Y_AXIS] = new_pos1;
// FIXME. The following two are wrong, since the parameter t is
// not linear in the distance.
bez_target[Z_AXIS] = interp(position[Z_AXIS], target[Z_AXIS], t);
bez_target[E_AXIS] = interp(position[E_AXIS], target[E_AXIS], t);
bez_target[Z_AXIS] = interp(pos[Z_AXIS], cart_target[Z_AXIS], t);
bez_target[E_CART] = interp(pos[E_CART], cart_target[E_CART], t);
clamp_to_software_endstops(bez_target);
#if HAS_UBL_AND_CURVES
float pos[XYZ] = { bez_target[X_AXIS], bez_target[Y_AXIS], bez_target[Z_AXIS] };
planner.apply_leveling(pos);
if (!planner.buffer_segment(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], bez_target[E_AXIS], fr_mm_s, active_extruder))
float bez_copy[XYZ] = { bez_target[X_AXIS], bez_target[Y_AXIS], bez_target[Z_AXIS] };
planner.apply_leveling(bez_copy);
if (!planner.buffer_segment(bez_copy[X_AXIS], bez_copy[Y_AXIS], bez_copy[Z_AXIS], bez_target[E_CART], fr_mm_s, active_extruder))
break;
#else
if (!planner.buffer_line_kinematic(bez_target, fr_mm_s, extruder))

View File

@ -159,7 +159,7 @@ void check_print_job_recovery() {
#endif
dtostrf(job_recovery_info.current_position[Z_AXIS] + 2, 1, 3, str_1);
dtostrf(job_recovery_info.current_position[E_AXIS]
dtostrf(job_recovery_info.current_position[E_CART]
#if ENABLED(SAVE_EACH_CMD_MODE)
- 5
#endif

View File

@ -135,9 +135,8 @@ uint8_t Stepper::steps_per_isr;
#endif
uint8_t Stepper::oversampling_factor;
int32_t Stepper::delta_error[XYZE] = { 0 };
uint32_t Stepper::advance_dividend[XYZE] = { 0 },
int32_t Stepper::delta_error[NUM_AXIS] = { 0 };
uint32_t Stepper::advance_dividend[NUM_AXIS] = { 0 },
Stepper::advance_divisor = 0,
Stepper::step_events_completed = 0, // The number of step events executed in the current block
Stepper::accelerate_until, // The point from where we need to stop acceleration
@ -180,14 +179,19 @@ uint32_t Stepper::nextMainISR = 0;
#endif // LIN_ADVANCE
int32_t Stepper::ticks_nominal = -1;
#if DISABLED(S_CURVE_ACCELERATION)
uint32_t Stepper::acc_step_rate; // needed for deceleration start point
#endif
volatile int32_t Stepper::endstops_trigsteps[XYZ];
volatile int32_t Stepper::count_position[NUM_AXIS] = { 0 };
int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
volatile int32_t Stepper::endstops_trigsteps[XYZ],
Stepper::count_position[NUM_AXIS] = { 0 };
int8_t Stepper::count_direction[NUM_AXIS] = {
1, 1, 1, 1
#if ENABLED(HANGPRINTER)
, 1
#endif
};
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#define DUAL_ENDSTOP_APPLY_STEP(A,V) \
@ -260,6 +264,28 @@ int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
#define Z_APPLY_STEP(v,Q) Z_STEP_WRITE(v)
#endif
/**
* Hangprinter's mapping {A,B,C,D} <-> {X,Y,Z,E1} happens here.
* If you have two extruders: {A,B,C,D} <-> {X,Y,Z,E2}
* ... etc up to max 4 extruders.
* Place D connector on your first "free" extruder output.
*/
#if ENABLED(HANGPRINTER)
#define A_APPLY_DIR(v,Q) X_APPLY_DIR(v,Q)
#define A_APPLY_STEP(v,Q) X_APPLY_STEP(v,Q)
#define B_APPLY_DIR(v,Q) Y_APPLY_DIR(v,Q)
#define B_APPLY_STEP(v,Q) Y_APPLY_STEP(v,Q)
#define C_APPLY_DIR(v,Q) Z_APPLY_DIR(v,Q)
#define C_APPLY_STEP(v,Q) Z_APPLY_STEP(v,Q)
#define __D_APPLY(I,T,v) E##I##_##T##_WRITE(v)
#define _D_APPLY(I,T,v) __D_APPLY(I,T,v)
#define D_APPLY_DIR(v,Q) _D_APPLY(EXTRUDERS, DIR, v)
#define D_APPLY_STEP(v,Q) _D_APPLY(EXTRUDERS, STEP, v)
#endif
#if DISABLED(MIXING_EXTRUDER)
#define E_APPLY_STEP(v,Q) E_STEP_WRITE(active_extruder, v)
#endif
@ -357,6 +383,9 @@ void Stepper::set_directions() {
#if HAS_Z_DIR
SET_STEP_DIR(Z); // C
#endif
#if ENABLED(HANGPRINTER)
SET_STEP_DIR(D);
#endif
#if DISABLED(LIN_ADVANCE)
#if ENABLED(MIXING_EXTRUDER)
@ -1251,6 +1280,12 @@ void Stepper::isr() {
* call to this method that might cause variation in the timing. The aim
* is to keep pulse timing as regular as possible.
*/
#if ENABLED(UNREGISTERED_MOVE_SUPPORT)
#define COUNT_IT current_block->count_it
#else
#define COUNT_IT true
#endif
void Stepper::stepper_pulse_phase_isr() {
// If we must abort the current block, do so!
@ -1289,7 +1324,7 @@ void Stepper::stepper_pulse_phase_isr() {
delta_error[_AXIS(AXIS)] += advance_dividend[_AXIS(AXIS)]; \
if (delta_error[_AXIS(AXIS)] >= 0) { \
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), 0); \
count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
if (COUNT_IT) count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
} \
}while(0)
@ -1302,22 +1337,37 @@ void Stepper::stepper_pulse_phase_isr() {
}while(0)
// Pulse start
#if HAS_X_STEP
PULSE_START(X);
#endif
#if HAS_Y_STEP
PULSE_START(Y);
#endif
#if HAS_Z_STEP
PULSE_START(Z);
#endif
#if ENABLED(HANGPRINTER)
#if HAS_A_STEP
PULSE_START(A);
#endif
#if HAS_B_STEP
PULSE_START(B);
#endif
#if HAS_C_STEP
PULSE_START(C);
#endif
#if HAS_D_STEP
PULSE_START(D);
#endif
#else
#if HAS_X_STEP
PULSE_START(X);
#endif
#if HAS_Y_STEP
PULSE_START(Y);
#endif
#if HAS_Z_STEP
PULSE_START(Z);
#endif
#endif // HANGPRINTER
// Pulse E/Mixing extruders
#if ENABLED(LIN_ADVANCE)
// Tick the E axis, correct error term and update position
delta_error[E_AXIS] += advance_dividend[E_AXIS];
if (delta_error[E_AXIS] >= 0) {
count_position[E_AXIS] += count_direction[E_AXIS];
if (COUNT_IT) count_position[E_AXIS] += count_direction[E_AXIS];
delta_error[E_AXIS] -= advance_divisor;
// Don't step E here - But remember the number of steps to perform
@ -1329,7 +1379,7 @@ void Stepper::stepper_pulse_phase_isr() {
// Tick the E axis
delta_error[E_AXIS] += advance_dividend[E_AXIS];
if (delta_error[E_AXIS] >= 0) {
count_position[E_AXIS] += count_direction[E_AXIS];
if (COUNT_IT) count_position[E_AXIS] += count_direction[E_AXIS];
delta_error[E_AXIS] -= advance_divisor;
}
@ -1354,15 +1404,29 @@ void Stepper::stepper_pulse_phase_isr() {
// Add the delay needed to ensure the maximum driver rate is enforced
if (signed(added_step_ticks) > 0) pulse_end += hal_timer_t(added_step_ticks);
// Pulse stop
#if HAS_X_STEP
PULSE_STOP(X);
#endif
#if HAS_Y_STEP
PULSE_STOP(Y);
#endif
#if HAS_Z_STEP
PULSE_STOP(Z);
#if ENABLED(HANGPRINTER)
#if HAS_A_STEP
PULSE_STOP(A);
#endif
#if HAS_B_STEP
PULSE_STOP(B);
#endif
#if HAS_C_STEP
PULSE_STOP(C);
#endif
#if HAS_D_STEP
PULSE_STOP(D);
#endif
#else
#if HAS_X_STEP
PULSE_STOP(X);
#endif
#if HAS_Y_STEP
PULSE_STOP(Y);
#endif
#if HAS_Z_STEP
PULSE_STOP(Z);
#endif
#endif
#if DISABLED(LIN_ADVANCE)
@ -1531,8 +1595,11 @@ uint32_t Stepper::stepper_block_phase_isr() {
// Sync block? Sync the stepper counts and return
while (TEST(current_block->flag, BLOCK_BIT_SYNC_POSITION)) {
_set_position(
current_block->position[A_AXIS], current_block->position[B_AXIS],
current_block->position[C_AXIS], current_block->position[E_AXIS]
current_block->position[A_AXIS], current_block->position[B_AXIS], current_block->position[C_AXIS],
#if ENABLED(HANGPRINTER)
current_block->position[D_AXIS],
#endif
current_block->position[E_AXIS]
);
planner.discard_current_block();
@ -2015,7 +2082,12 @@ void Stepper::init() {
* This allows get_axis_position_mm to correctly
* derive the current XYZ position later on.
*/
void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c,
#if ENABLED(HANGPRINTER)
const int32_t &d,
#endif
const int32_t &e
) {
#if CORE_IS_XY
// corexy positioning
// these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html
@ -2037,6 +2109,9 @@ void Stepper::_set_position(const int32_t &a, const int32_t &b, const int32_t &c
count_position[X_AXIS] = a;
count_position[Y_AXIS] = b;
count_position[Z_AXIS] = c;
#if ENABLED(HANGPRINTER)
count_position[D_AXIS] = d;
#endif
#endif
count_position[E_AXIS] = e;
}
@ -2103,31 +2178,38 @@ void Stepper::report_positions() {
const int32_t xpos = count_position[X_AXIS],
ypos = count_position[Y_AXIS],
#if ENABLED(HANGPRINTER)
dpos = count_position[D_AXIS],
#endif
zpos = count_position[Z_AXIS];
if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT();
#if CORE_IS_XY || CORE_IS_XZ || IS_DELTA || IS_SCARA
#if CORE_IS_XY || CORE_IS_XZ || IS_DELTA || IS_SCARA || ENABLED(HANGPRINTER)
SERIAL_PROTOCOLPGM(MSG_COUNT_A);
#else
SERIAL_PROTOCOLPGM(MSG_COUNT_X);
#endif
SERIAL_PROTOCOL(xpos);
#if CORE_IS_XY || CORE_IS_YZ || IS_DELTA || IS_SCARA
#if CORE_IS_XY || CORE_IS_YZ || IS_DELTA || IS_SCARA || ENABLED(HANGPRINTER)
SERIAL_PROTOCOLPGM(" B:");
#else
SERIAL_PROTOCOLPGM(" Y:");
#endif
SERIAL_PROTOCOL(ypos);
#if CORE_IS_XZ || CORE_IS_YZ || IS_DELTA
#if CORE_IS_XZ || CORE_IS_YZ || IS_DELTA || ENABLED(HANGPRINTER)
SERIAL_PROTOCOLPGM(" C:");
#else
SERIAL_PROTOCOLPGM(" Z:");
#endif
SERIAL_PROTOCOL(zpos);
#if ENABLED(HANGPRINTER)
SERIAL_PROTOCOLPAIR(" D:", dpos);
#endif
SERIAL_EOL();
}

View File

@ -270,8 +270,8 @@ class Stepper {
#endif
// Delta error variables for the Bresenham line tracer
static int32_t delta_error[XYZE];
static uint32_t advance_dividend[XYZE],
static int32_t delta_error[NUM_AXIS];
static uint32_t advance_dividend[NUM_AXIS],
advance_divisor,
step_events_completed, // The number of step events executed in the current block
accelerate_until, // The point from where we need to stop acceleration
@ -425,11 +425,21 @@ class Stepper {
#endif
// Set the current position in steps
inline static void set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e) {
inline static void set_position(const int32_t &a, const int32_t &b, const int32_t &c
#if ENABLED(HANGPRINTER)
, const int32_t &d
#endif
, const int32_t &e
) {
planner.synchronize();
const bool was_enabled = STEPPER_ISR_ENABLED();
if (was_enabled) DISABLE_STEPPER_DRIVER_INTERRUPT();
_set_position(a, b, c, e);
_set_position(a, b, c
#if ENABLED(HANGPRINTER)
, d
#endif
, e
);
if (was_enabled) ENABLE_STEPPER_DRIVER_INTERRUPT();
}
@ -447,7 +457,12 @@ class Stepper {
private:
// Set the current position in steps
static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c, const int32_t &e);
static void _set_position(const int32_t &a, const int32_t &b, const int32_t &c
#if ENABLED(HANGPRINTER)
, const int32_t &d
#endif
, const int32_t &e
);
// Set direction bits for all steppers
static void set_directions();

View File

@ -55,7 +55,7 @@ void TWIBus::address(const uint8_t adr) {
#endif
}
void TWIBus::addbyte(const char c) {
void TWIBus::addbyte(const byte c) {
if (this->buffer_s >= COUNT(this->buffer)) return;
this->buffer[this->buffer_s++] = c;
#if ENABLED(DEBUG_TWIBUS)
@ -63,7 +63,7 @@ void TWIBus::addbyte(const char c) {
#endif
}
void TWIBus::addbytes(char src[], uint8_t bytes) {
void TWIBus::addbytes(byte src[], uint8_t bytes) {
#if ENABLED(DEBUG_TWIBUS)
debug(PSTR("addbytes"), bytes);
#endif
@ -138,7 +138,7 @@ void TWIBus::relay(const uint8_t bytes) {
echodata(bytes, PSTR("i2c-reply"), this->addr);
}
uint8_t TWIBus::capture(char *dst, const uint8_t bytes) {
uint8_t TWIBus::capture(byte *dst, const uint8_t bytes) {
this->reset();
uint8_t count = 0;
while (count < bytes && Wire.available())

View File

@ -33,6 +33,13 @@
typedef void (*twiReceiveFunc_t)(int bytes);
typedef void (*twiRequestFunc_t)();
#if ENABLED(MECHADUINO_I2C_COMMANDS)
typedef union {
float fval;
byte bval[sizeof(float)];
} i2cFloat;
#endif
#define TWIBUS_BUFFER_SIZE 32
/**
@ -99,7 +106,7 @@ class TWIBus {
*
* @param c a data byte
*/
void addbyte(const char c);
void addbyte(const byte c);
/**
* @brief Add some bytes to the buffer
@ -109,7 +116,7 @@ class TWIBus {
* @param src source data address
* @param bytes the number of bytes to add
*/
void addbytes(char src[], uint8_t bytes);
void addbytes(byte src[], uint8_t bytes);
/**
* @brief Add a null-terminated string to the buffer
@ -172,7 +179,7 @@ class TWIBus {
* @param bytes the number of bytes to request
* @return the number of bytes captured to the buffer
*/
uint8_t capture(char *dst, const uint8_t bytes);
uint8_t capture(byte *dst, const uint8_t bytes);
/**
* @brief Flush the i2c bus.

View File

@ -76,7 +76,7 @@
// ignore the status of the g26_debug_flag
if (*title != '!' && !g26_debug_flag) return;
const float de = destination[E_AXIS] - current_position[E_AXIS];
const float de = destination[E_CART] - current_position[E_CART];
if (de == 0.0) return; // Printing moves only
@ -97,7 +97,7 @@
SERIAL_ECHOPGM(", ");
SERIAL_ECHO_F(current_position[Z_AXIS], 6);
SERIAL_ECHOPGM(", ");
SERIAL_ECHO_F(current_position[E_AXIS], 6);
SERIAL_ECHO_F(current_position[E_CART], 6);
SERIAL_ECHOPGM(" ) destination=( ");
debug_echo_axis(X_AXIS);
SERIAL_ECHOPGM(", ");

View File

@ -46,8 +46,8 @@
*/
#if ENABLED(SKEW_CORRECTION)
// For skew correction just adjust the destination point and we're done
float start[XYZE] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS] },
end[XYZE] = { destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS] };
float start[XYZE] = { current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_CART] },
end[XYZE] = { destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_CART] };
planner.skew(start[X_AXIS], start[Y_AXIS], start[Z_AXIS]);
planner.skew(end[X_AXIS], end[Y_AXIS], end[Z_AXIS]);
#else
@ -64,7 +64,7 @@
SERIAL_ECHOPAIR(" ubl.line_to_destination_cartesian(xe=", destination[X_AXIS]);
SERIAL_ECHOPAIR(", ye=", destination[Y_AXIS]);
SERIAL_ECHOPAIR(", ze=", destination[Z_AXIS]);
SERIAL_ECHOPAIR(", ee=", destination[E_AXIS]);
SERIAL_ECHOPAIR(", ee=", destination[E_CART]);
SERIAL_CHAR(')');
SERIAL_EOL();
debug_current_and_destination(PSTR("Start of ubl.line_to_destination_cartesian()"));
@ -85,7 +85,7 @@
+ UBL_Z_RAISE_WHEN_OFF_MESH
#endif
;
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_AXIS], feed_rate, extruder);
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + z_raise, end[E_CART], feed_rate, extruder);
set_current_from_destination();
if (g26_debug_flag)
@ -112,7 +112,7 @@
// Undefined parts of the Mesh in z_values[][] are NAN.
// Replace NAN corrections with 0.0 to prevent NAN propagation.
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_AXIS], feed_rate, extruder);
planner.buffer_segment(end[X_AXIS], end[Y_AXIS], end[Z_AXIS] + (isnan(z0) ? 0.0 : z0), end[E_CART], feed_rate, extruder);
if (g26_debug_flag)
debug_current_and_destination(PSTR("FINAL_MOVE in ubl.line_to_destination_cartesian()"));
@ -149,7 +149,7 @@
const bool use_x_dist = adx > ady;
float on_axis_distance = use_x_dist ? dx : dy,
e_position = end[E_AXIS] - start[E_AXIS],
e_position = end[E_CART] - start[E_CART],
z_position = end[Z_AXIS] - start[Z_AXIS];
const float e_normalized_dist = e_position / on_axis_distance,
@ -198,11 +198,11 @@
if (ry != start[Y_AXIS]) {
if (!inf_normalized_flag) {
on_axis_distance = use_x_dist ? rx - start[X_AXIS] : ry - start[Y_AXIS];
e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist;
e_position = start[E_CART] + on_axis_distance * e_normalized_dist;
z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist;
}
else {
e_position = end[E_AXIS];
e_position = end[E_CART];
z_position = end[Z_AXIS];
}
@ -249,11 +249,11 @@
if (rx != start[X_AXIS]) {
if (!inf_normalized_flag) {
on_axis_distance = use_x_dist ? rx - start[X_AXIS] : ry - start[Y_AXIS];
e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move
e_position = start[E_CART] + on_axis_distance * e_normalized_dist; // is based on X or Y because this is a horizontal move
z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist;
}
else {
e_position = end[E_AXIS];
e_position = end[E_CART];
z_position = end[Z_AXIS];
}
@ -308,11 +308,11 @@
if (!inf_normalized_flag) {
on_axis_distance = use_x_dist ? rx - start[X_AXIS] : next_mesh_line_y - start[Y_AXIS];
e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist;
e_position = start[E_CART] + on_axis_distance * e_normalized_dist;
z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist;
}
else {
e_position = end[E_AXIS];
e_position = end[E_CART];
z_position = end[Z_AXIS];
}
if (!planner.buffer_segment(rx, next_mesh_line_y, z_position + z0, e_position, feed_rate, extruder))
@ -331,11 +331,11 @@
if (!inf_normalized_flag) {
on_axis_distance = use_x_dist ? next_mesh_line_x - start[X_AXIS] : ry - start[Y_AXIS];
e_position = start[E_AXIS] + on_axis_distance * e_normalized_dist;
e_position = start[E_CART] + on_axis_distance * e_normalized_dist;
z_position = start[Z_AXIS] + on_axis_distance * z_normalized_dist;
}
else {
e_position = end[E_AXIS];
e_position = end[E_CART];
z_position = end[Z_AXIS];
}
@ -378,7 +378,12 @@
#if ENABLED(DELTA) // apply delta inverse_kinematics
DELTA_IK(raw);
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_AXIS], fr, active_extruder);
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_CART], fr, active_extruder);
#elif ENABLED(HANGPRINTER) // apply hangprinter inverse_kinematics
HANGPRINTER_IK(raw);
planner.buffer_segment(line_lengths[A_AXIS], line_lengths[B_AXIS], line_lengths[C_AXIS], line_lengths[D_AXIS], in_raw[E_CART], fr, active_extruder);
#elif IS_SCARA // apply scara inverse_kinematics (should be changed to save raw->logical->raw)
@ -391,11 +396,11 @@
scara_oldB = delta[B_AXIS];
float s_feedrate = MAX(adiff, bdiff) * scara_feed_factor;
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_AXIS], s_feedrate, active_extruder);
planner.buffer_segment(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], in_raw[E_CART], s_feedrate, active_extruder);
#else // CARTESIAN
planner.buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], in_raw[E_AXIS], fr, active_extruder);
planner.buffer_segment(raw[X_AXIS], raw[Y_AXIS], raw[Z_AXIS], in_raw[E_CART], fr, active_extruder);
#endif
}
@ -427,7 +432,7 @@
rtarget[X_AXIS] - current_position[X_AXIS],
rtarget[Y_AXIS] - current_position[Y_AXIS],
rtarget[Z_AXIS] - current_position[Z_AXIS],
rtarget[E_AXIS] - current_position[E_AXIS]
rtarget[E_CART] - current_position[E_CART]
};
const float cartesian_xy_mm = HYPOT(total[X_AXIS], total[Y_AXIS]); // total horizontal xy distance
@ -454,7 +459,7 @@
total[X_AXIS] * inv_segments,
total[Y_AXIS] * inv_segments,
total[Z_AXIS] * inv_segments,
total[E_AXIS] * inv_segments
total[E_CART] * inv_segments
};
// Note that E segment distance could vary slightly as z mesh height
@ -464,7 +469,7 @@
current_position[X_AXIS],
current_position[Y_AXIS],
current_position[Z_AXIS],
current_position[E_AXIS]
current_position[E_CART]
};
// Only compute leveling per segment if ubl active and target below z_fade_height.

View File

@ -3077,7 +3077,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
#if IS_KINEMATIC
manual_move_offset += diff;
#else
current_position[E_AXIS] += diff;
current_position[E_CART] += diff;
#endif
manual_move_to_current(E_AXIS
#if E_MANUAL > 1
@ -3107,7 +3107,7 @@ void lcd_quick_feedback(const bool clear_buttons) {
#endif // E_MANUAL > 2
}
#endif // E_MANUAL > 1
lcd_implementation_drawedit(pos_label, ftostr41sign(current_position[E_AXIS]
lcd_implementation_drawedit(pos_label, ftostr41sign(current_position[E_CART]
#if IS_KINEMATIC
+ manual_move_offset
#endif