@ -211,72 +211,37 @@ bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
int feedmultiply = 100 ; //100->1 200->2
int saved_feedmultiply ;
int extrudemultiply = 100 ; //100->1 200->2
int extruder_multiply [ EXTRUDERS ] = { 100
# if EXTRUDERS > 1
, 100
# if EXTRUDERS > 2
, 100
# if EXTRUDERS > 3
, 100
# endif
# endif
# endif
} ;
int extruder_multiply [ EXTRUDERS ] = ARRAY_BY_EXTRUDERS ( 100 , 100 , 100 , 100 ) ;
bool volumetric_enabled = false ;
float filament_size [ EXTRUDERS ] = { DEFAULT_NOMINAL_FILAMENT_DIA
# if EXTRUDERS > 1
, DEFAULT_NOMINAL_FILAMENT_DIA
# if EXTRUDERS > 2
, DEFAULT_NOMINAL_FILAMENT_DIA
# if EXTRUDERS > 3
, DEFAULT_NOMINAL_FILAMENT_DIA
# endif
# endif
# endif
} ;
float volumetric_multiplier [ EXTRUDERS ] = { 1.0
# if EXTRUDERS > 1
, 1.0
# if EXTRUDERS > 2
, 1.0
# if EXTRUDERS > 3
, 1.0
# endif
# endif
# endif
} ;
float current_position [ NUM_AXIS ] = { 0.0 , 0.0 , 0.0 , 0.0 } ;
float home_offset [ 3 ] = { 0 , 0 , 0 } ;
float filament_size [ EXTRUDERS ] = ARRAY_BY_EXTRUDERS ( DEFAULT_NOMINAL_FILAMENT_DIA , DEFAULT_NOMINAL_FILAMENT_DIA , DEFAULT_NOMINAL_FILAMENT_DIA , DEFAULT_NOMINAL_FILAMENT_DIA ) ;
float volumetric_multiplier [ EXTRUDERS ] = ARRAY_BY_EXTRUDERS ( 1.0 , 1.0 , 1.0 , 1.0 ) ;
float current_position [ NUM_AXIS ] = { 0.0 } ;
float home_offset [ 3 ] = { 0 } ;
# ifdef DELTA
float endstop_adj [ 3 ] = { 0 , 0 , 0 } ;
float endstop_adj [ 3 ] = { 0 } ;
# elif defined(Z_DUAL_ENDSTOPS)
float z_endstop_adj = 0 ;
# endif
float min_pos [ 3 ] = { X_MIN_POS , Y_MIN_POS , Z_MIN_POS } ;
float max_pos [ 3 ] = { X_MAX_POS , Y_MAX_POS , Z_MAX_POS } ;
bool axis_known_position [ 3 ] = { false , false , false } ;
bool axis_known_position [ 3 ] = { false } ;
// Extruder offset
# if EXTRUDERS > 1
# ifndef EXTRUDER_OFFSET_X
# define EXTRUDER_OFFSET_X 0
# endif
# ifndef EXTRUDER_OFFSET_Y
# define EXTRUDER_OFFSET_Y 0
# endif
# ifndef DUAL_X_CARRIAGE
# define NUM_EXTRUDER_OFFSETS 2 // only in XY plane
# else
# define NUM_EXTRUDER_OFFSETS 3 // supports offsets in XYZ plane
# endif
float extruder_offset [ NUM_EXTRUDER_OFFSETS ] [ EXTRUDERS ] = {
# if defined(EXTRUDER_OFFSET_X)
EXTRUDER_OFFSET_X
# else
0
# endif
,
# if defined(EXTRUDER_OFFSET_Y)
EXTRUDER_OFFSET_Y
# else
0
# endif
} ;
# define _EXY { EXTRUDER_OFFSET_X, EXTRUDER_OFFSET_Y }
float extruder_offset [ EXTRUDERS ] [ NUM_EXTRUDER_OFFSETS ] = ARRAY_BY_EXTRUDERS ( _EXY , _EXY , _EXY , _EXY ) ;
# endif
uint8_t active_extruder = 0 ;
@ -295,28 +260,8 @@ int fanSpeed = 0;
# ifdef FWRETRACT
bool autoretract_enabled = false ;
bool retracted [ EXTRUDERS ] = { false
# if EXTRUDERS > 1
, false
# if EXTRUDERS > 2
, false
# if EXTRUDERS > 3
, false
# endif
# endif
# endif
} ;
bool retracted_swap [ EXTRUDERS ] = { false
# if EXTRUDERS > 1
, false
# if EXTRUDERS > 2
, false
# if EXTRUDERS > 3
, false
# endif
# endif
# endif
} ;
bool retracted [ EXTRUDERS ] = { false } ;
bool retracted_swap [ EXTRUDERS ] = { false } ;
float retract_length = RETRACT_LENGTH ;
float retract_length_swap = RETRACT_LENGTH_SWAP ;
@ -385,9 +330,9 @@ const char errormagic[] PROGMEM = "Error:";
const char echomagic [ ] PROGMEM = " echo: " ;
const char axis_codes [ NUM_AXIS ] = { ' X ' , ' Y ' , ' Z ' , ' E ' } ;
static float destination [ NUM_AXIS ] = { 0 , 0 , 0 , 0 } ;
static float destination [ NUM_AXIS ] = { 0 } ;
static float offset [ 3 ] = { 0 , 0 , 0 } ;
static float offset [ 3 ] = { 0 } ;
# ifndef DELTA
static bool home_all_axis = true ;
@ -993,7 +938,7 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
// second X-carriage offset when homed - otherwise X2_HOME_POS is used.
// This allow soft recalibration of the second extruder offset position without firmware reflash
// (through the M218 command).
return ( extruder_offset [ X_AXIS ] [ 1 ] > 0 ) ? extruder_offset [ X_AXIS ] [ 1 ] : X2_HOME_POS ;
return ( extruder_offset [ 1 ] [ X_AXIS ] > 0 ) ? extruder_offset [ 1 ] [ X_AXIS ] : X2_HOME_POS ;
}
static int x_home_dir ( int extruder ) {
@ -1017,14 +962,14 @@ static void axis_is_at_home(int axis) {
if ( active_extruder ! = 0 ) {
current_position [ X_AXIS ] = x_home_pos ( active_extruder ) ;
min_pos [ X_AXIS ] = X2_MIN_POS ;
max_pos [ X_AXIS ] = max ( extruder_offset [ X_AXIS ] [ 1 ] , X2_MAX_POS ) ;
max_pos [ X_AXIS ] = max ( extruder_offset [ 1 ] [ X_AXIS ] , X2_MAX_POS ) ;
return ;
}
else if ( dual_x_carriage_mode = = DXC_DUPLICATION_MODE ) {
current_position [ X_AXIS ] = base_home_pos ( X_AXIS ) + home_offset [ X_AXIS ] ;
min_pos [ X_AXIS ] = base_min_pos ( X_AXIS ) + home_offset [ X_AXIS ] ;
max_pos [ X_AXIS ] = min ( base_max_pos ( X_AXIS ) + home_offset [ X_AXIS ] ,
max ( extruder_offset [ X_AXIS ] [ 1 ] , X2_MAX_POS ) - duplicate_extruder_x_offset ) ;
max ( extruder_offset [ 1 ] [ X_AXIS ] , X2_MAX_POS ) - duplicate_extruder_x_offset ) ;
return ;
}
}
@ -1077,12 +1022,18 @@ static void axis_is_at_home(int axis) {
# endif
}
/**
* Shorthand to tell the planner our current position ( in mm ) .
*/
inline void sync_plan_position ( ) {
plan_set_position ( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
}
# ifdef ENABLE_AUTO_BED_LEVELING
# ifdef AUTO_BED_LEVELING_GRID
# ifndef DELTA
static void set_bed_level_equation_lsq ( double * plane_equation_coefficients )
{
static void set_bed_level_equation_lsq ( double * plane_equation_coefficients ) {
vector_3 planeNormal = vector_3 ( - plane_equation_coefficients [ 0 ] , - plane_equation_coefficients [ 1 ] , 1 ) ;
planeNormal . debug ( " planeNormal " ) ;
plan_bed_level_matrix = matrix_3x3 : : create_look_at ( planeNormal ) ;
@ -1096,9 +1047,9 @@ static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
//corrected_position.debug("position after");
current_position [ X_AXIS ] = corrected_position . x ;
current_position [ Y_AXIS ] = corrected_position . y ;
current_position [ Z_AXIS ] = corrected_position. z ;
current_position [ Z_AXIS ] = zprobe_zoffset; // was: corrected_position.z
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
}
# endif
@ -1124,9 +1075,9 @@ static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float
vector_3 corrected_position = plan_get_position ( ) ;
current_position [ X_AXIS ] = corrected_position . x ;
current_position [ Y_AXIS ] = corrected_position . y ;
current_position [ Z_AXIS ] = corrected_position. z ;
current_position [ Z_AXIS ] = zprobe_zoffset; // was: corrected_position.z
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
}
# endif // AUTO_BED_LEVELING_GRID
@ -1172,18 +1123,14 @@ static void run_z_probe() {
endstops_hit_on_purpose ( ) ;
// move back down slowly to find bed
if ( homing_bump_divisor [ Z_AXIS ] > = 1 )
{
if ( homing_bump_divisor [ Z_AXIS ] > = 1 ) {
feedrate = homing_feedrate [ Z_AXIS ] / homing_bump_divisor [ Z_AXIS ] ;
}
else
{
else {
feedrate = homing_feedrate [ Z_AXIS ] / 10 ;
SERIAL_ECHOLN ( " Warning: The Homing Bump Feedrate Divisor cannot be less then 1 " ) ;
}
zPosition - = home_retract_mm ( Z_AXIS ) * 2 ;
plan_buffer_line ( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , zPosition , current_position [ E_AXIS ] , feedrate / 60 , active_extruder ) ;
st_synchronize ( ) ;
@ -1191,7 +1138,7 @@ static void run_z_probe() {
current_position [ Z_AXIS ] = st_get_position_mm ( Z_AXIS ) ;
// make sure the planner knows where we are as it may be a bit different than we last said to move to
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif
}
@ -1471,7 +1418,7 @@ static void homeaxis(int axis) {
# endif
current_position [ axis ] = 0 ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# ifndef Z_PROBE_SLED
@ -1497,7 +1444,7 @@ static void homeaxis(int axis) {
st_synchronize ( ) ;
current_position [ axis ] = 0 ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
destination [ axis ] = - home_retract_mm ( axis ) * axis_home_dir ;
plan_buffer_line ( destination [ X_AXIS ] , destination [ Y_AXIS ] , destination [ Z_AXIS ] , destination [ E_AXIS ] , feedrate / 60 , active_extruder ) ;
st_synchronize ( ) ;
@ -1520,7 +1467,7 @@ static void homeaxis(int axis) {
if ( axis = = Z_AXIS )
{
feedrate = homing_feedrate [ axis ] ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
if ( axis_home_dir > 0 )
{
destination [ axis ] = ( - 1 ) * fabs ( z_endstop_adj ) ;
@ -1540,7 +1487,7 @@ static void homeaxis(int axis) {
# ifdef DELTA
// retrace by the amount specified in endstop_adj
if ( endstop_adj [ axis ] * axis_home_dir < 0 ) {
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
destination [ axis ] = endstop_adj [ axis ] ;
plan_buffer_line ( destination [ X_AXIS ] , destination [ Y_AXIS ] , destination [ Z_AXIS ] , destination [ E_AXIS ] , feedrate / 60 , active_extruder ) ;
st_synchronize ( ) ;
@ -1596,7 +1543,7 @@ void refresh_cmd_timeout(void)
calculate_delta ( current_position ) ; // change cartesian kinematic to delta kinematic;
plan_set_position ( delta [ X_AXIS ] , delta [ Y_AXIS ] , delta [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
# else
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif
prepare_move ( ) ;
}
@ -1612,7 +1559,7 @@ void refresh_cmd_timeout(void)
calculate_delta ( current_position ) ; // change cartesian kinematic to delta kinematic;
plan_set_position ( delta [ X_AXIS ] , delta [ Y_AXIS ] , delta [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
# else
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif
//prepare_move();
}
@ -1789,7 +1736,7 @@ inline void gcode_G28() {
// Move all carriages up together until the first endstop is hit.
for ( int i = X_AXIS ; i < = Z_AXIS ; i + + ) current_position [ i ] = 0 ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
for ( int i = X_AXIS ; i < = Z_AXIS ; i + + ) destination [ i ] = 3 * Z_MAX_LENGTH ;
feedrate = 1.732 * homing_feedrate [ X_AXIS ] ;
@ -1829,7 +1776,7 @@ inline void gcode_G28() {
extruder_duplication_enabled = false ;
# endif
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
destination [ X_AXIS ] = 1.5 * max_length ( X_AXIS ) * x_axis_home_dir ;
destination [ Y_AXIS ] = 1.5 * max_length ( Y_AXIS ) * home_dir ( Y_AXIS ) ;
feedrate = homing_feedrate [ X_AXIS ] ;
@ -1844,7 +1791,7 @@ inline void gcode_G28() {
axis_is_at_home ( X_AXIS ) ;
axis_is_at_home ( Y_AXIS ) ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
destination [ X_AXIS ] = current_position [ X_AXIS ] ;
destination [ Y_AXIS ] = current_position [ Y_AXIS ] ;
plan_buffer_line ( destination [ X_AXIS ] , destination [ Y_AXIS ] , destination [ Z_AXIS ] , destination [ E_AXIS ] , feedrate / 60 , active_extruder ) ;
@ -1921,7 +1868,7 @@ inline void gcode_G28() {
feedrate = XY_TRAVEL_SPEED / 60 ;
current_position [ Z_AXIS ] = 0 ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
plan_buffer_line ( destination [ X_AXIS ] , destination [ Y_AXIS ] , destination [ Z_AXIS ] , destination [ E_AXIS ] , feedrate , active_extruder ) ;
st_synchronize ( ) ;
current_position [ X_AXIS ] = destination [ X_AXIS ] ;
@ -1973,7 +1920,7 @@ inline void gcode_G28() {
if ( home_all_axis | | code_seen ( axis_codes [ Z_AXIS ] ) )
current_position [ Z_AXIS ] + = zprobe_zoffset ; //Add Z_Probe offset (the distance is negative)
# endif
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif // else DELTA
@ -1998,7 +1945,7 @@ inline void gcode_G28() {
plan_buffer_line ( destination [ X_AXIS ] , destination [ Y_AXIS ] , destination [ Z_AXIS ] , destination [ E_AXIS ] , feedrate , active_extruder ) ;
st_synchronize ( ) ;
current_position [ Z_AXIS ] = MESH_HOME_SEARCH_Z ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
mbl . active = 1 ;
}
# endif
@ -2069,7 +2016,7 @@ inline void gcode_G28() {
int ix , iy ;
if ( probe_point = = 0 ) {
current_position [ Z_AXIS ] = MESH_HOME_SEARCH_Z ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
} else {
ix = ( probe_point - 1 ) % MESH_NUM_X_POINTS ;
iy = ( probe_point - 1 ) / MESH_NUM_X_POINTS ;
@ -2242,7 +2189,7 @@ inline void gcode_G28() {
current_position [ X_AXIS ] = uncorrected_position . x ;
current_position [ Y_AXIS ] = uncorrected_position . y ;
current_position [ Z_AXIS ] = uncorrected_position . z ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif
}
@ -2443,7 +2390,7 @@ inline void gcode_G28() {
apply_rotation_xyz ( plan_bed_level_matrix , x_tmp , y_tmp , z_tmp ) ; //Apply the correction sending the probe offset
current_position [ Z_AXIS ] = z_tmp - real_z + current_position [ Z_AXIS ] ; //The difference is added to current position and sent to planner.
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
}
# endif // !DELTA
@ -2504,7 +2451,7 @@ inline void gcode_G92() {
didXYZ = true ;
}
}
if ( didXYZ ) plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
if ( didXYZ ) sync_plan_position( ) ;
}
# ifdef ULTIPANEL
@ -3762,23 +3709,23 @@ inline void gcode_M206() {
inline void gcode_M218 ( ) {
if ( setTargetedHotend ( 218 ) ) return ;
if ( code_seen ( ' X ' ) ) extruder_offset [ X_AXIS] [ tmp_extruder] = code_value ( ) ;
if ( code_seen ( ' Y ' ) ) extruder_offset [ Y_AXIS] [ tmp_extruder] = code_value ( ) ;
if ( code_seen ( ' X ' ) ) extruder_offset [ tmp_extruder] [ X_AXIS ] = code_value ( ) ;
if ( code_seen ( ' Y ' ) ) extruder_offset [ tmp_extruder] [ Y_AXIS ] = code_value ( ) ;
# ifdef DUAL_X_CARRIAGE
if ( code_seen ( ' Z ' ) ) extruder_offset [ Z_AXIS] [ tmp_extruder] = code_value ( ) ;
if ( code_seen ( ' Z ' ) ) extruder_offset [ tmp_extruder] [ Z_AXIS ] = code_value ( ) ;
# endif
SERIAL_ECHO_START ;
SERIAL_ECHOPGM ( MSG_HOTEND_OFFSET ) ;
for ( tmp_extruder = 0 ; tmp_extruder < EXTRUDERS ; tmp_extruder + + ) {
SERIAL_ECHO ( " " ) ;
SERIAL_ECHO ( extruder_offset [ X_AXIS] [ tmp_extruder] ) ;
SERIAL_ECHO ( extruder_offset [ tmp_extruder] [ X_AXIS ] ) ;
SERIAL_ECHO ( " , " ) ;
SERIAL_ECHO ( extruder_offset [ Y_AXIS] [ tmp_extruder] ) ;
SERIAL_ECHO ( extruder_offset [ tmp_extruder] [ Y_AXIS ] ) ;
# ifdef DUAL_X_CARRIAGE
SERIAL_ECHO ( " , " ) ;
SERIAL_ECHO ( extruder_offset [ Z_AXIS] [ tmp_extruder] ) ;
SERIAL_ECHO ( extruder_offset [ tmp_extruder] [ Z_AXIS ] ) ;
# endif
}
SERIAL_EOL ;
@ -4469,13 +4416,13 @@ inline void gcode_M503() {
SERIAL_ECHO_START ;
SERIAL_ECHOPGM ( MSG_HOTEND_OFFSET ) ;
SERIAL_ECHO ( " " ) ;
SERIAL_ECHO ( extruder_offset [ X_AXIS ] [ 0 ] ) ;
SERIAL_ECHO ( extruder_offset [ 0 ] [ X_AXIS ] ) ;
SERIAL_ECHO ( " , " ) ;
SERIAL_ECHO ( extruder_offset [ Y_AXIS ] [ 0 ] ) ;
SERIAL_ECHO ( extruder_offset [ 0 ] [ Y_AXIS ] ) ;
SERIAL_ECHO ( " " ) ;
SERIAL_ECHO ( duplicate_extruder_x_offset ) ;
SERIAL_ECHO ( " , " ) ;
SERIAL_ECHOLN ( extruder_offset [ Y_AXIS ] [ 1 ] ) ;
SERIAL_ECHOLN ( extruder_offset [ 1 ] [ Y_AXIS ] ) ;
break ;
case DXC_FULL_CONTROL_MODE :
case DXC_AUTO_PARK_MODE :
@ -4610,11 +4557,11 @@ inline void gcode_T() {
// apply Y & Z extruder offset (x offset is already used in determining home pos)
current_position [ Y_AXIS ] = current_position [ Y_AXIS ] -
extruder_offset [ Y_AXIS] [ active_extruder] +
extruder_offset [ Y_AXIS] [ tmp_extruder] ;
extruder_offset [ active_extruder] [ Y_AXIS ] +
extruder_offset [ tmp_extruder] [ Y_AXIS ] ;
current_position [ Z_AXIS ] = current_position [ Z_AXIS ] -
extruder_offset [ Z_AXIS] [ active_extruder] +
extruder_offset [ Z_AXIS] [ tmp_extruder] ;
extruder_offset [ active_extruder] [ Z_AXIS ] +
extruder_offset [ tmp_extruder] [ Z_AXIS ] ;
active_extruder = tmp_extruder ;
@ -4644,7 +4591,7 @@ inline void gcode_T() {
# else // !DUAL_X_CARRIAGE
// Offset extruder (only by XY)
for ( int i = X_AXIS ; i < = Y_AXIS ; i + + )
current_position [ i ] + = extruder_offset [ i] [ tmp_extruder] - extruder_offset [ i] [ active_extruder] ;
current_position [ i ] + = extruder_offset [ tmp_extruder] [ i ] - extruder_offset [ active_extruder] [ i ] ;
// Set the new active extruder and position
active_extruder = tmp_extruder ;
# endif // !DUAL_X_CARRIAGE
@ -4653,7 +4600,7 @@ inline void gcode_T() {
//sent position to plan_set_position();
plan_set_position ( delta [ X_AXIS ] , delta [ Y_AXIS ] , delta [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
# else
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
# endif
// Move to the old position if 'F' was in the parameters
if ( make_move & & ! Stopped ) prepare_move ( ) ;
@ -5494,7 +5441,7 @@ for (int s = 1; s <= steps; s++) {
plan_set_position ( inactive_extruder_x_pos , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
plan_buffer_line ( current_position [ X_AXIS ] + duplicate_extruder_x_offset , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] ,
current_position [ E_AXIS ] , max_feedrate [ X_AXIS ] , 1 ) ;
plan_set_position( current_position [ X_AXIS ] , current_position [ Y_AXIS ] , current_position [ Z_AXIS ] , current_position [ E_AXIS ] ) ;
sync_plan_position( ) ;
st_synchronize ( ) ;
extruder_duplication_enabled = true ;
active_extruder_parked = false ;